gtsam/matlab/examples/Pose2SLAMExample.m

77 lines
2.5 KiB
Matlab
Raw Normal View History

2012-01-28 10:51:35 +08:00
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
2012-06-04 04:12:12 +08:00
% GTSAM Copyright 2010, Georgia Tech Research Corporation,
2012-01-28 10:51:35 +08:00
% Atlanta, Georgia 30332-0415
% All Rights Reserved
% Authors: Frank Dellaert, et al. (see THANKS for the full author list)
2012-06-04 04:12:12 +08:00
%
2012-01-28 10:51:35 +08:00
% See LICENSE for the license information
%
% @brief Simple robotics example using the pre-built planar SLAM domain
% @author Alex Cunningham
% @author Frank Dellaert
% @author Chris Beall
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Assumptions
% - All values are axis aligned
% - Robot poses are facing along the X axis (horizontal, to the right in images)
% - We have full odometry for measurements
% - The robot is on a grid, moving 2 meters each step
%% Create graph container and add factors to it
graph = pose2SLAM.Graph;
2012-01-28 10:51:35 +08:00
%% Add prior
import gtsam.*
2012-01-28 10:51:35 +08:00
% gaussian for prior
priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin
priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
graph.addPosePrior(1, priorMean, priorNoise); % add directly to graph
2012-01-28 10:51:35 +08:00
%% Add odometry
import gtsam.*
2012-01-28 10:51:35 +08:00
% general noisemodel for odometry
odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(1, 2, Pose2(2.0, 0.0, 0.0 ), odometryNoise);
graph.addRelativePose(2, 3, Pose2(2.0, 0.0, pi/2), odometryNoise);
graph.addRelativePose(3, 4, Pose2(2.0, 0.0, pi/2), odometryNoise);
graph.addRelativePose(4, 5, Pose2(2.0, 0.0, pi/2), odometryNoise);
2012-01-28 10:51:35 +08:00
2012-06-04 04:12:12 +08:00
%% Add pose constraint
import gtsam.*
model = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
graph.addRelativePose(5, 2, Pose2(2.0, 0.0, pi/2), model);
2012-01-28 10:51:35 +08:00
% print
2012-06-04 04:14:23 +08:00
graph.print(sprintf('\nFactor graph:\n'));
2012-01-28 10:51:35 +08:00
%% Initialize to noisy points
import gtsam.*
initialEstimate = pose2SLAM.Values;
initialEstimate.insertPose(1, Pose2(0.5, 0.0, 0.2 ));
initialEstimate.insertPose(2, Pose2(2.3, 0.1,-0.2 ));
initialEstimate.insertPose(3, Pose2(4.1, 0.1, pi/2));
initialEstimate.insertPose(4, Pose2(4.0, 2.0, pi ));
initialEstimate.insertPose(5, Pose2(2.1, 2.1,-pi/2));
2012-06-04 04:12:12 +08:00
initialEstimate.print(sprintf('\nInitial estimate:\n'));
2012-01-28 10:51:35 +08:00
%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd
result = graph.optimize(initialEstimate,1);
2012-06-04 04:12:12 +08:00
result.print(sprintf('\nFinal result:\n'));
2012-06-05 11:51:21 +08:00
%% Plot Covariance Ellipses
2012-06-12 12:38:05 +08:00
cla;
X=result.poses();
plot(X(:,1),X(:,2),'k*-'); hold on
2012-06-05 11:51:21 +08:00
plot([result.pose(5).x;result.pose(2).x],[result.pose(5).y;result.pose(2).y],'r-');
marginals = graph.marginals(result);
2012-06-05 11:51:21 +08:00
for i=1:result.size()
pose_i = result.pose(i);
P = marginals.marginalCovariance(i)
plotPose2(pose_i,'g',P);
2012-06-05 11:51:21 +08:00
end
axis([-0.6 4.8 -1 1])
2012-06-05 11:51:21 +08:00
axis equal
view(2)