Merged in feature/gtsam-tutorial (pull request #262)
Updated gtsam.lyx Approved-by: Frank Dellaert <dellaert@cc.gatech.edu>release/4.3a0
commit
05d973ac70
|
@ -0,0 +1,7 @@
|
|||
// add unary measurement factors, like GPS, on all three poses
|
||||
noiseModel::Diagonal::shared_ptr unaryNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y
|
||||
graph.add(boost::make_shared<UnaryFactor>(1, 0.0, 0.0, unaryNoise));
|
||||
graph.add(boost::make_shared<UnaryFactor>(2, 2.0, 0.0, unaryNoise));
|
||||
graph.add(boost::make_shared<UnaryFactor>(3, 4.0, 0.0, unaryNoise));
|
||||
|
|
@ -0,0 +1,14 @@
|
|||
class UnaryFactor: public NoiseModelFactor1<Pose2> {
|
||||
double mx_, my_; ///< X and Y measurements
|
||||
|
||||
public:
|
||||
UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
|
||||
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}
|
||||
|
||||
Vector evaluateError(const Pose2& q,
|
||||
boost::optional<Matrix&> H = boost::none) const
|
||||
{
|
||||
if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0).finished();
|
||||
return (Vector(2) << q.x() - mx_, q.y() - my_).finished();
|
||||
}
|
||||
};
|
|
@ -0,0 +1,18 @@
|
|||
Final Result:
|
||||
Values with 3 values:
|
||||
Value 1: (-1.5e-14, 1.3e-15, -1.4e-16)
|
||||
Value 2: (2, 3.1e-16, -8.5e-17)
|
||||
Value 3: (4, -6e-16, -8.2e-17)
|
||||
|
||||
x1 covariance:
|
||||
0.0083 4.3e-19 -1.1e-18
|
||||
4.3e-19 0.0094 -0.0031
|
||||
-1.1e-18 -0.0031 0.0082
|
||||
x2 covariance:
|
||||
0.0071 2.5e-19 -3.4e-19
|
||||
2.5e-19 0.0078 -0.0011
|
||||
-3.4e-19 -0.0011 0.0082
|
||||
x3 covariance:
|
||||
0.0083 4.4e-19 1.2e-18
|
||||
4.4e-19 0.0094 0.0031
|
||||
1.2e-18 0.0031 0.018
|
|
@ -0,0 +1,15 @@
|
|||
// Create an empty nonlinear factor graph
|
||||
NonlinearFactorGraph graph;
|
||||
|
||||
// Add a Gaussian prior on pose x_1
|
||||
Pose2 priorMean(0.0, 0.0, 0.0);
|
||||
noiseModel::Diagonal::shared_ptr priorNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
|
||||
graph.add(PriorFactor<Pose2>(1, priorMean, priorNoise));
|
||||
|
||||
// Add two odometry factors
|
||||
Pose2 odometry(2.0, 0.0, 0.0);
|
||||
noiseModel::Diagonal::shared_ptr odometryNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
||||
graph.add(BetweenFactor<Pose2>(1, 2, odometry, odometryNoise));
|
||||
graph.add(BetweenFactor<Pose2>(2, 3, odometry, odometryNoise));
|
|
@ -0,0 +1,6 @@
|
|||
// Query the marginals
|
||||
cout.precision(2);
|
||||
Marginals marginals(graph, result);
|
||||
cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl;
|
||||
cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl;
|
||||
cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl;
|
|
@ -0,0 +1,9 @@
|
|||
// create (deliberatly inaccurate) initial estimate
|
||||
Values initial;
|
||||
initial.insert(1, Pose2(0.5, 0.0, 0.2));
|
||||
initial.insert(2, Pose2(2.3, 0.1, -0.2));
|
||||
initial.insert(3, Pose2(4.1, 0.1, 0.1));
|
||||
|
||||
// optimize using Levenberg-Marquardt optimization
|
||||
Values result = LevenbergMarquardtOptimizer(graph, initial).optimize();
|
||||
|
|
@ -0,0 +1,11 @@
|
|||
Factor Graph:
|
||||
size: 3
|
||||
factor 0: PriorFactor on 1
|
||||
prior mean: (0, 0, 0)
|
||||
noise model: diagonal sigmas [0.3; 0.3; 0.1];
|
||||
factor 1: BetweenFactor(1,2)
|
||||
measured: (2, 0, 0)
|
||||
noise model: diagonal sigmas [0.2; 0.2; 0.1];
|
||||
factor 2: BetweenFactor(2,3)
|
||||
measured: (2, 0, 0)
|
||||
noise model: diagonal sigmas [0.2; 0.2; 0.1];
|
|
@ -0,0 +1,11 @@
|
|||
Initial Estimate:
|
||||
Values with 3 values:
|
||||
Value 1: (0.5, 0, 0.2)
|
||||
Value 2: (2.3, 0.1, -0.2)
|
||||
Value 3: (4.1, 0.1, 0.1)
|
||||
|
||||
Final Result:
|
||||
Values with 3 values:
|
||||
Value 1: (-1.8e-16, 8.7e-18, -9.1e-19)
|
||||
Value 2: (2, 7.4e-18, -2.5e-18)
|
||||
Value 3: (4, -1.8e-18, -3.1e-18)
|
|
@ -0,0 +1,12 @@
|
|||
x1 covariance:
|
||||
0.09 1.1e-47 5.7e-33
|
||||
1.1e-47 0.09 1.9e-17
|
||||
5.7e-33 1.9e-17 0.01
|
||||
x2 covariance:
|
||||
0.13 4.7e-18 2.4e-18
|
||||
4.7e-18 0.17 0.02
|
||||
2.4e-18 0.02 0.02
|
||||
x3 covariance:
|
||||
0.17 2.7e-17 8.4e-18
|
||||
2.7e-17 0.37 0.06
|
||||
8.4e-18 0.06 0.03
|
|
@ -0,0 +1,25 @@
|
|||
% Create graph container and add factors to it
|
||||
graph = NonlinearFactorGraph;
|
||||
|
||||
% Create keys for variables
|
||||
i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3);
|
||||
j1 = symbol('l',1); j2 = symbol('l',2);
|
||||
|
||||
% Add prior
|
||||
priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin
|
||||
priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
|
||||
% add directly to graph
|
||||
graph.add(PriorFactorPose2(i1, priorMean, priorNoise));
|
||||
|
||||
% Add odometry
|
||||
odometry = Pose2(2.0, 0.0, 0.0);
|
||||
odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
|
||||
graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise));
|
||||
graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise));
|
||||
|
||||
% Add bearing/range measurement factors
|
||||
degrees = pi/180;
|
||||
brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]);
|
||||
graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(8), brNoise));
|
||||
graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise));
|
||||
graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise));
|
|
@ -0,0 +1,7 @@
|
|||
>> result
|
||||
Values with 5 values:
|
||||
l1: (2, 2)
|
||||
l2: (4, 2)
|
||||
x1: (-1.8e-16, 5.1e-17, -1.5e-17)
|
||||
x2: (2, -5.8e-16, -4.6e-16)
|
||||
x3: (4, -3.1e-15, -4.6e-16)
|
|
@ -0,0 +1,15 @@
|
|||
%% Initialize graph, initial estimate, and odometry noise
|
||||
datafile = findExampleDataFile('w100.graph');
|
||||
model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 5*pi/180]);
|
||||
[graph,initial] = load2D(datafile, model);
|
||||
|
||||
%% Add a Gaussian prior on pose x_0
|
||||
priorMean = Pose2(0, 0, 0);
|
||||
priorNoise = noiseModel.Diagonal.Sigmas([0.01; 0.01; 0.01]);
|
||||
graph.add(PriorFactorPose2(0, priorMean, priorNoise));
|
||||
|
||||
%% Optimize using Levenberg-Marquardt optimization and get marginals
|
||||
optimizer = LevenbergMarquardtOptimizer(graph, initial);
|
||||
result = optimizer.optimizeSafely;
|
||||
marginals = Marginals(graph, result);
|
||||
|
|
@ -0,0 +1,16 @@
|
|||
NonlinearFactorGraph graph;
|
||||
noiseModel::Diagonal::shared_ptr priorNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
|
||||
graph.add(PriorFactor<Pose2>(1, Pose2(0, 0, 0), priorNoise));
|
||||
|
||||
// Add odometry factors
|
||||
noiseModel::Diagonal::shared_ptr model =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
||||
graph.add(BetweenFactor<Pose2>(1, 2, Pose2(2, 0, 0 ), model));
|
||||
graph.add(BetweenFactor<Pose2>(2, 3, Pose2(2, 0, M_PI_2), model));
|
||||
graph.add(BetweenFactor<Pose2>(3, 4, Pose2(2, 0, M_PI_2), model));
|
||||
graph.add(BetweenFactor<Pose2>(4, 5, Pose2(2, 0, M_PI_2), model));
|
||||
|
||||
// Add the loop closure constraint
|
||||
graph.add(BetweenFactor<Pose2>(5, 2, Pose2(2, 0, M_PI_2), model));
|
||||
|
|
@ -0,0 +1,14 @@
|
|||
graph = NonlinearFactorGraph;
|
||||
priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
|
||||
graph.add(PriorFactorPose2(1, Pose2(0, 0, 0), priorNoise));
|
||||
|
||||
%% Add odometry factors
|
||||
model = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
|
||||
graph.add(BetweenFactorPose2(1, 2, Pose2(2, 0, 0 ), model));
|
||||
graph.add(BetweenFactorPose2(2, 3, Pose2(2, 0, pi/2), model));
|
||||
graph.add(BetweenFactorPose2(3, 4, Pose2(2, 0, pi/2), model));
|
||||
graph.add(BetweenFactorPose2(4, 5, Pose2(2, 0, pi/2), model));
|
||||
|
||||
%% Add pose constraint
|
||||
graph.add(BetweenFactorPose2(5, 2, Pose2(2, 0, pi/2), model));
|
||||
|
|
@ -0,0 +1,12 @@
|
|||
%% Initialize graph, initial estimate, and odometry noise
|
||||
datafile = findExampleDataFile('sphere2500.txt');
|
||||
model = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 0.05; 0.05; 0.05]);
|
||||
[graph,initial] = load3D(datafile, model, true, 2500);
|
||||
plot3DTrajectory(initial, 'g-', false); % Plot Initial Estimate
|
||||
|
||||
%% Read again, now with all constraints, and optimize
|
||||
graph = load3D(datafile, model, false, 2500);
|
||||
graph.add(NonlinearEqualityPose3(0, initial.atPose3(0)));
|
||||
optimizer = LevenbergMarquardtOptimizer(graph, initial);
|
||||
result = optimizer.optimizeSafely();
|
||||
plot3DTrajectory(result, 'r-', false); axis equal;
|
|
@ -0,0 +1,9 @@
|
|||
%% Add factors for all measurements
|
||||
noise = noiseModel.Isotropic.Sigma(2, measurementNoiseSigma);
|
||||
for i = 1:length(Z),
|
||||
for k = 1:length(Z{i})
|
||||
j = J{i}{k};
|
||||
G.add(GenericProjectionFactorCal3_S2(
|
||||
Z{i}{k}, noise, symbol('x', i), symbol('p', j), K));
|
||||
end
|
||||
end
|
|
@ -0,0 +1,24 @@
|
|||
int relinearizeInterval = 3;
|
||||
NonlinearISAM isam(relinearizeInterval);
|
||||
|
||||
// ... first frame initialization omitted ...
|
||||
|
||||
// Loop over the different poses, adding the observations to iSAM
|
||||
for (size_t i = 1; i < poses.size(); ++i) {
|
||||
|
||||
// Add factors for each landmark observation
|
||||
NonlinearFactorGraph graph;
|
||||
for (size_t j = 0; j < points.size(); ++j) {
|
||||
graph.add(
|
||||
GenericProjectionFactor<Pose3, Point3, Cal3_S2>
|
||||
(z[i][j], noise,Symbol('x', i), Symbol('l', j), K)
|
||||
);
|
||||
}
|
||||
|
||||
// Add an initial guess for the current pose
|
||||
Values initialEstimate;
|
||||
initialEstimate.insert(Symbol('x', i), initial_x[i]);
|
||||
|
||||
// Update iSAM with the new factors
|
||||
isam.update(graph, initialEstimate);
|
||||
}
|
|
@ -0,0 +1,7 @@
|
|||
>> graph.error(initialEstimate)
|
||||
ans =
|
||||
20.1086
|
||||
|
||||
>> graph.error(result)
|
||||
ans =
|
||||
8.2631e-18
|
|
@ -0,0 +1,23 @@
|
|||
>> priorNoise
|
||||
diagonal sigmas [0.3; 0.3; 0.1];
|
||||
|
||||
>> graph
|
||||
size: 6
|
||||
factor 0: PriorFactor on 1
|
||||
prior mean: (0, 0, 0)
|
||||
noise model: diagonal sigmas [0.3; 0.3; 0.1];
|
||||
factor 1: BetweenFactor(1,2)
|
||||
measured: (2, 0, 0)
|
||||
noise model: diagonal sigmas [0.2; 0.2; 0.1];
|
||||
factor 2: BetweenFactor(2,3)
|
||||
measured: (2, 0, 1.6)
|
||||
noise model: diagonal sigmas [0.2; 0.2; 0.1];
|
||||
factor 3: BetweenFactor(3,4)
|
||||
measured: (2, 0, 1.6)
|
||||
noise model: diagonal sigmas [0.2; 0.2; 0.1];
|
||||
factor 4: BetweenFactor(4,5)
|
||||
measured: (2, 0, 1.6)
|
||||
noise model: diagonal sigmas [0.2; 0.2; 0.1];
|
||||
factor 5: BetweenFactor(5,2)
|
||||
measured: (2, 0, 1.6)
|
||||
noise model: diagonal sigmas [0.2; 0.2; 0.1];
|
|
@ -0,0 +1,7 @@
|
|||
>> whos
|
||||
Name Size Bytes Class
|
||||
graph 1x1 112 gtsam.NonlinearFactorGraph
|
||||
priorNoise 1x1 112 gtsam.noiseModel.Diagonal
|
||||
model 1x1 112 gtsam.noiseModel.Diagonal
|
||||
initialEstimate 1x1 112 gtsam.Values
|
||||
optimizer 1x1 112 gtsam.LevenbergMarquardtOptimizer
|
|
@ -0,0 +1,124 @@
|
|||
\global\long\def\Vector#1{{\bf #1}}
|
||||
\global\long\def\Matrix#1{{\bf #1}}
|
||||
|
||||
|
||||
\global\long\def\eq#1{equation (\ref{eq:=0000231})}
|
||||
|
||||
|
||||
\global\long\def\eye#1{\Vector{I_{#1}}}
|
||||
|
||||
|
||||
\global\long\def\leftsparrow#1{\stackrel{#1}{\leftarrow}}
|
||||
\global\long\def\rightsparrow#1{\stackrel{#1}{\rightarrow}}
|
||||
\global\long\def\chain{\mathcal{M}}
|
||||
|
||||
|
||||
\global\long\def\define{\stackrel{\Delta}{=}}
|
||||
|
||||
|
||||
\global\long\def\argmin#1{\mathop{\textrm{argmin \,}}_{#1}}
|
||||
|
||||
|
||||
\global\long\def\Norm#1{\Vert#1\Vert}
|
||||
\global\long\def\SqrNorm#1{\Vert#1\Vert^{2}}
|
||||
\global\long\def\Ltwo#1{\mathcal{L}^{2}\left(#1\right)}
|
||||
|
||||
|
||||
\global\long\def\Normal#1#2#3{\mathcal{N}(#1;#2,#3)}
|
||||
|
||||
|
||||
\global\long\def\LogNormal#1#2#3{ (#1-#2)^{T} #3^{-1} (#1-#2) }
|
||||
|
||||
|
||||
\global\long\def\SqrMah#1#2#3{\Vert{#1}-{#2}\Vert_{#3}^{2}}
|
||||
|
||||
|
||||
\global\long\def\SqrZMah#1#2{\Vert{#1}\Vert_{#2}^{2}}
|
||||
|
||||
|
||||
\global\long\def\Info#1#2#3{\mathcal{N}^{-1}(#1;#2,#3)}
|
||||
|
||||
|
||||
\providecommand{\half}{\frac{1}{2}}
|
||||
|
||||
\global\long\def\Mah#1#2#3{\Vert{#1}-{#2}\Vert_{#3}}
|
||||
\global\long\def\MahDeriv#1#2#3#4{\biggl(\deriv{#2}{#4}\biggr)^{T} #3^{-1} (#1-#2)}
|
||||
|
||||
|
||||
\global\long\def\argmin#1{\mathop{\textrm{argmin \,}}_{#1}}
|
||||
\global\long\def\argmax#1{\mathop{\textrm{argmax \,}}_{#1}}
|
||||
|
||||
|
||||
|
||||
|
||||
\global\long\def\deriv#1#2{\frac{\partial#1}{\partial#2}}
|
||||
|
||||
|
||||
\global\long\def\at#1#2{#1\biggr\rvert_{#2}}
|
||||
|
||||
|
||||
\global\long\def\Jac#1#2#3{ \at{\deriv{#1}{#2}} {#3} }
|
||||
|
||||
|
||||
|
||||
|
||||
\global\long\def\Rone{\mathbb{R}}
|
||||
\global\long\def\Pone{\mathbb{P}}
|
||||
|
||||
|
||||
\global\long\def\Rtwo{\mathbb{R}^{2}}
|
||||
\global\long\def\Ptwo{\mathbb{P}^{2}}
|
||||
|
||||
|
||||
\global\long\def\Stwo{\mathbb{S}^{2}}
|
||||
\global\long\def\Complex{\mathbb{C}}
|
||||
|
||||
|
||||
\global\long\def\Z{\mathbb{Z}}
|
||||
\global\long\def\Rplus{\mathbb{R}^{+}}
|
||||
|
||||
|
||||
\global\long\def\SOtwo{SO(2)}
|
||||
\global\long\def\sotwo{\mathfrak{so(2)}}
|
||||
\global\long\def\skew#1{[#1]_{+}}
|
||||
|
||||
|
||||
\global\long\def\SEtwo{SE(2)}
|
||||
\global\long\def\setwo{\mathfrak{se(2)}}
|
||||
\global\long\def\Skew#1{[#1]_{\times}}
|
||||
|
||||
|
||||
\global\long\def\Rthree{\mathbb{R}^{3}}
|
||||
\global\long\def\Pthree{\mathbb{P}^{3}}
|
||||
|
||||
|
||||
\global\long\def\SOthree{SO(3)}
|
||||
\global\long\def\sothree{\mathfrak{so(3)}}
|
||||
|
||||
|
||||
\global\long\def\Rsix{\mathbb{R}^{6}}
|
||||
\global\long\def\SEthree{SE(3)}
|
||||
\global\long\def\sethree{\mathfrak{se(3)}}
|
||||
|
||||
|
||||
\global\long\def\Rn{\mathbb{R}^{n}}
|
||||
|
||||
|
||||
\global\long\def\Afftwo{Aff(2)}
|
||||
\global\long\def\afftwo{\mathfrak{aff(2)}}
|
||||
|
||||
|
||||
\global\long\def\SLthree{SL(3)}
|
||||
\global\long\def\slthree{\mathfrak{sl(3)}}
|
||||
|
||||
|
||||
|
||||
|
||||
\global\long\def\stirling#1#2{\genfrac{\{}{\}}{0pt}{}{#1}{#2}}
|
||||
|
||||
|
||||
\global\long\def\matlabscript#1#2{\begin{itemize}\item[]\lstinputlisting[caption=#2,label=#1]{#1.m}\end{itemize}}
|
||||
|
||||
|
||||
\global\long\def\atan{\mathop{atan2}}
|
||||
|
|
@ -0,0 +1,133 @@
|
|||
@String { ICCV = {Intl. Conf. on Computer Vision (ICCV)} }
|
||||
@String { IROS = {IEEE/RSJ Intl. Conf. on Intelligent Robots and Systems (IROS)} }
|
||||
@String { CVPR = {IEEE Conf. on Computer Vision and Pattern Recognition (CVPR)} }
|
||||
@String { IJRR = {Intl. J. of Robotics Research} }
|
||||
@String { RAS = {Robotics and Autonomous Systems} }
|
||||
@String { TRO = {{IEEE} Trans. Robotics} }
|
||||
@String { IT = {{IEEE} Trans. Inform. Theory} }
|
||||
@String { ISRR = {Proc. of the Intl. Symp. of Robotics Research (ISRR)} }
|
||||
|
||||
@inproceedings{Davison03iccv,
|
||||
title = {Real-Time Simultaneous Localisation and Mapping with a Single Camera},
|
||||
author = {A.J. Davison},
|
||||
booktitle = ICCV,
|
||||
year = {2003},
|
||||
month = {Oct},
|
||||
pages = {1403-1410}
|
||||
}
|
||||
|
||||
@inproceedings{Dellaert10iros,
|
||||
title = {Subgraph-preconditioned Conjugate Gradient for Large Scale SLAM},
|
||||
author = {F. Dellaert and J. Carlson and V. Ila and K. Ni and C.E. Thorpe},
|
||||
booktitle = IROS,
|
||||
year = {2010},
|
||||
}
|
||||
|
||||
@inproceedings{Dellaert99b,
|
||||
title = {Using the Condensation Algorithm for Robust, Vision-based Mobile Robot Localization},
|
||||
author = {F. Dellaert and D. Fox and W. Burgard and S. Thrun},
|
||||
booktitle = CVPR,
|
||||
year = {1999}
|
||||
}
|
||||
|
||||
@article{Dellaert06ijrr,
|
||||
title = {Square {Root} {SAM}: Simultaneous Localization and Mapping via Square Root Information Smoothing},
|
||||
author = {F. Dellaert and M. Kaess},
|
||||
journal = IJRR,
|
||||
year = {2006},
|
||||
month = {Dec},
|
||||
number = {12},
|
||||
pages = {1181--1203},
|
||||
volume = {25},
|
||||
}
|
||||
|
||||
@article{DurrantWhyte06ram,
|
||||
title = {Simultaneous Localisation and Mapping ({SLAM}): Part {I} The Essential Algorithms},
|
||||
author = {H.F. Durrant-Whyte and T. Bailey},
|
||||
journal = {Robotics \& Automation Magazine},
|
||||
year = {2006},
|
||||
month = {Jun},
|
||||
}
|
||||
|
||||
@inproceedings{Jian11iccv,
|
||||
title = {Generalized Subgraph Preconditioners for Large-Scale Bundle Adjustment},
|
||||
author = {Y.-D. Jian and D. Balcan and F. Dellaert},
|
||||
booktitle = ICCV,
|
||||
year = {2011},
|
||||
}
|
||||
|
||||
@article{Kaess09ras,
|
||||
title = {Covariance Recovery from a Square Root Information Matrix for Data Association},
|
||||
author = {M. Kaess and F. Dellaert},
|
||||
journal = RAS,
|
||||
year = {2009},
|
||||
}
|
||||
|
||||
@article{Kaess12ijrr,
|
||||
title = {{iSAM2}: Incremental Smoothing and Mapping Using the {B}ayes Tree},
|
||||
author = {M. Kaess and H. Johannsson and R. Roberts and V. Ila and J. Leonard and F. Dellaert},
|
||||
journal = IJRR,
|
||||
year = {2012},
|
||||
month = {Feb},
|
||||
pages = {217--236},
|
||||
volume = {31},
|
||||
issue = {2},
|
||||
}
|
||||
|
||||
@article{Kaess08tro,
|
||||
title = {{iSAM}: Incremental Smoothing and Mapping},
|
||||
author = {M. Kaess and A. Ranganathan and F. Dellaert},
|
||||
journal = TRO,
|
||||
year = {2008},
|
||||
month = {Dec},
|
||||
number = {6},
|
||||
pages = {1365-1378},
|
||||
volume = {24},
|
||||
}
|
||||
|
||||
@book{Koller09book,
|
||||
title = {Probabilistic Graphical Models: Principles and Techniques},
|
||||
author = {D. Koller and N. Friedman},
|
||||
publisher = {The MIT Press},
|
||||
year = {2009}
|
||||
}
|
||||
|
||||
@Article{Kschischang01it,
|
||||
title = {Factor Graphs and the Sum-Product Algorithm},
|
||||
Author = {F.R. Kschischang and B.J. Frey and H-A. Loeliger},
|
||||
Journal = IT,
|
||||
Year = {2001},
|
||||
|
||||
Month = {February},
|
||||
Number = {2},
|
||||
Volume = {47}
|
||||
}
|
||||
|
||||
@article{Loeliger04spm,
|
||||
Title = {An Introduction to Factor Graphs},
|
||||
Author = {H.-A. Loeliger},
|
||||
Journal = {IEEE Signal Processing Magazine},
|
||||
Year = {2004},
|
||||
|
||||
Month = {January},
|
||||
Pages = {28--41}
|
||||
}
|
||||
|
||||
@inproceedings{Nister04cvpr2,
|
||||
title = {Visual Odometry},
|
||||
author = {D. Nist\'er and O. Naroditsky and J. Bergen},
|
||||
booktitle = CVPR,
|
||||
year = {2004},
|
||||
month = {Jun},
|
||||
pages = {652-659},
|
||||
volume = {1}
|
||||
}
|
||||
|
||||
@InProceedings{Smith87b,
|
||||
title = {A stochastic map for uncertain spatial relationships},
|
||||
Author = {R. Smith and M. Self and P. Cheeseman},
|
||||
Booktitle = ISRR,
|
||||
Year = {1988},
|
||||
Pages = {467-474}
|
||||
}
|
||||
|
File diff suppressed because it is too large
Load Diff
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,101 @@
|
|||
%PDF-1.4
|
||||
%Çì<C387>¢
|
||||
5 0 obj
|
||||
<</Length 6 0 R/Filter /FlateDecode>>
|
||||
stream
|
||||
xœÍ˜ÏŠ$7ÆïõuLQlKþw
„œgg °<>
a&°ä<C2B0>×<EFBFBD>ì²,¹«Yº‡Þ!»,ßÈ®Ÿ¿’,Õ~ÝøÝµ¿ãçç·íçOyÿòÏöu1aÙ“‹JÙߦâK"ð~Ýb‰R¸¢Èª×íÏí÷ýï<C3BD> ¶?û¿›ßÿâ¿mµ$@ç÷€!Cʼ¿(1G¶ú>]QdÕëiŸ×íysW÷?¯}>=óíÊ3Ÿob}>íë^ßâúö½K‚ šBNP‹<50>ÑNÁ9(aøõ…߸並<C2A9>Ÿßö_^8J^þØŽñ{%H…Ê‚‡êËþò¶ýð“ƒøãË_Û¯/ÛÓæ)UˆÕRMÅ`
ÍpMEÁn…òÄ VÒ唨d„š-ÑTÑÐÑTÞATPŕȸB*`˜TQ&Ñ”I•û™B (9/L^‰Rd
ÑTÑÐÑTÞA”`Y]òÆ%t)Z—TQ&Ñ”I•û™Ðä´º”ˆ²‡l]RÅ
ÍMåDä äÕ¥`]*ùââQÅ0
Í0MåL%B¢• '…ìøš0Dª(‘hJ¤ÊýDx“D+‘q‰RŽà¬Kª¦¡¦©¼ƒ‰¯Úˆ+M¢èÚ<C3A8>g]RE‰D3-j*÷E^ââ‘qi6ž_ ¿jU–V7£bH
|
||||
-Q·2¾–‚çšæ<O1-%œ‘
|
||||
ÿžÑ
ÒP¤5‘LÔHüÊ+µË¸xp5HþŠO°g‡B‰b¡4J lÔ½>ahçן‘V h‘†² ͨ‰d¢îõ ù"o
ø4
9ì½T¡D±P%P6êæÅAF~iĹÞÖu˜Dü+@k“(ÑŒšD&êæ7硤Py-lN§i`2
|
||||
Ìn™†²0ͨÉd¢îv‰áÐÓÅ40ÇM¾Š X—D±D%D6ê^—"çwNé4
L¦Dž›<C5BE>eÊÂ4£&“‰º×¥˜</¦<>ÿëGÆŸïüT}‚ÏPú×THàÂYн®}¾µÏ+™ÖÉB±3—V¬tN[ÃOßùÓò`#gÀ<Õ
|
||||
ÜêD±Ÿäxħ`>?Èy‚@c°Äæ‹ÞJèjïËöDzîÄãF\œàQe® ”Í^”ù·).{©c²—*ºŸ¯r¥˜(O¥r³†[ÏFÓ(Y§Q<íö<"Ríô%ƒFˆ¦Q²N£xÚ‰€d¢ØS¦ëE”h%ë4ªÕžÛ?=ðe>Òµï]_röÈ&¡=>÷ýöù§Ç×M£sqž×qTÌ\Y¢D9ßvçÏÍÐ^|EðÔ•±“£åø
|
||||
ðg%ynBÔFšù’øW€¡+ÃD£„öU³¬â~ÍO%<25>º€¥Ï·ä=a殤6<C2A4>1NAÅ(X9«b0«°òÍQÑlŒ•Úÿ|è³±bO<åÃz™êŒ2ÎiV
/¸AŒaNüÂZzq¿O%/}ÿ˜kq¤Ô¯´G^TP<çð޶i‰píðÓ¢+Až¯å²¥N¢µƒœÇP+µ#Í|FÏø1kÊ£wÇ@7«bºený•Ì"ç8é¼)ÉPË(R‡à|WrO¹#›Â©šÓ|1V‘›NWÉk—<6B>±æ~‹ëÓµpÖ›œA+GÎi•Ã
|
||||
]t˜¥e,~jm©ç’I—ïåCkë‘=þ‘½ôƒŠ‹2uß´º(3Vµ Æ\3Dm»\ÇQ¹t»l”(Rq”s·A+nî4Kƒ2vc´žæKš½išhî9ÚUɹ'UH±¬ÅM1Å=›•(Ú¬Æ"MrÙv–<76><Y+Eè´3É ¬rœÒ¬Nh™Š[ZOê¨$Ï¥ëG:=mÿF3#òendstream
|
||||
endobj
|
||||
6 0 obj
|
||||
1341
|
||||
endobj
|
||||
4 0 obj
|
||||
<</Type/Page/MediaBox [0 0 612 792]
|
||||
/Rotate 0/Parent 3 0 R
|
||||
/Resources<</ProcSet[/PDF /Text]
|
||||
/ExtGState 9 0 R
|
||||
/Font 10 0 R
|
||||
>>
|
||||
/Contents 5 0 R
|
||||
>>
|
||||
endobj
|
||||
3 0 obj
|
||||
<< /Type /Pages /Kids [
|
||||
4 0 R
|
||||
] /Count 1
|
||||
>>
|
||||
endobj
|
||||
1 0 obj
|
||||
<</Type /Catalog /Pages 3 0 R
|
||||
/Metadata 12 0 R
|
||||
>>
|
||||
endobj
|
||||
7 0 obj
|
||||
<</Type/ExtGState
|
||||
/OPM 1>>endobj
|
||||
9 0 obj
|
||||
<</R7
|
||||
7 0 R>>
|
||||
endobj
|
||||
10 0 obj
|
||||
<</R8
|
||||
8 0 R>>
|
||||
endobj
|
||||
8 0 obj
|
||||
<</BaseFont/Helvetica/Type/Font
|
||||
/Encoding 11 0 R/Subtype/Type1>>
|
||||
endobj
|
||||
11 0 obj
|
||||
<</Type/Encoding/Differences[
|
||||
45/minus]>>
|
||||
endobj
|
||||
12 0 obj
|
||||
<</Length 1324>>stream
|
||||
<?xpacket begin='' id='W5M0MpCehiHzreSzNTczkc9d'?>
|
||||
<?adobe-xap-filters esc="CRLF"?>
|
||||
<x:xmpmeta xmlns:x='adobe:ns:meta/' x:xmptk='XMP toolkit 2.9.1-13, framework 1.6'>
|
||||
<rdf:RDF xmlns:rdf='http://www.w3.org/1999/02/22-rdf-syntax-ns#' xmlns:iX='http://ns.adobe.com/iX/1.0/'>
|
||||
<rdf:Description rdf:about='6ea0c85a-ec69-11ec-0000-88f4c9fe0d6d' xmlns:pdf='http://ns.adobe.com/pdf/1.3/' pdf:Producer='Artifex Ghostscript 8.54'/>
|
||||
<rdf:Description rdf:about='6ea0c85a-ec69-11ec-0000-88f4c9fe0d6d' xmlns:xap='http://ns.adobe.com/xap/1.0/' xap:ModifyDate='2012-06-12' xap:CreateDate='2012-06-12'><xap:CreatorTool>Artifex Ghostscript 8.54 PDF Writer</xap:CreatorTool></rdf:Description>
|
||||
<rdf:Description rdf:about='6ea0c85a-ec69-11ec-0000-88f4c9fe0d6d' xmlns:xapMM='http://ns.adobe.com/xap/1.0/mm/' xapMM:DocumentID='6ea0c85a-ec69-11ec-0000-88f4c9fe0d6d'/>
|
||||
<rdf:Description rdf:about='6ea0c85a-ec69-11ec-0000-88f4c9fe0d6d' xmlns:dc='http://purl.org/dc/elements/1.1/' dc:format='application/pdf'><dc:title><rdf:Alt><rdf:li xml:lang='x-default'>/private/tmp/tpfd5bb1cf_55d8_447e_8f97_d6b24a262922.ps</rdf:li></rdf:Alt></dc:title></rdf:Description>
|
||||
</rdf:RDF>
|
||||
</x:xmpmeta>
|
||||
|
||||
|
||||
<?xpacket end='w'?>
|
||||
endstream
|
||||
endobj
|
||||
2 0 obj
|
||||
<</Producer(Artifex Ghostscript 8.54)
|
||||
/CreationDate(D:20120612011010)
|
||||
/ModDate(D:20120612011010)
|
||||
/Creator(MATLAB, The MathWorks, Inc. Version 7.13.0.564 \(R2011b\). Operating System: Darwin 11.4.0 Darwin Kernel Version 11.4.0: Mon Apr 9 19:32:15 PDT 2012; root:xnu-1699.26.8~1/RELEASE_X86_64 x86_64.)
|
||||
/Title(/private/tmp/tpfd5bb1cf_55d8_447e_8f97_d6b24a262922.ps)>>endobj
|
||||
xref
|
||||
0 13
|
||||
0000000000 65535 f
|
||||
0000001664 00000 n
|
||||
0000003341 00000 n
|
||||
0000001605 00000 n
|
||||
0000001446 00000 n
|
||||
0000000015 00000 n
|
||||
0000001426 00000 n
|
||||
0000001729 00000 n
|
||||
0000001829 00000 n
|
||||
0000001770 00000 n
|
||||
0000001799 00000 n
|
||||
0000001909 00000 n
|
||||
0000001967 00000 n
|
||||
trailer
|
||||
<< /Size 13 /Root 1 0 R /Info 2 0 R
|
||||
/ID [<0E15732D337F57A9CB2C0954A12E8EF8><0E15732D337F57A9CB2C0954A12E8EF8>]
|
||||
>>
|
||||
startxref
|
||||
3722
|
||||
%%EOF
|
Binary file not shown.
Binary file not shown.
File diff suppressed because one or more lines are too long
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Loading…
Reference in New Issue