gtsam/examples/matlab/Pose2SLAMExample.m

57 lines
2.2 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 = pose2SLAMGraph;
%% Add prior
% gaussian for prior
2012-06-03 13:25:05 +08:00
priorMean = gtsamPose2(0.0, 0.0, 0.0); % prior at origin
2012-06-04 04:12:12 +08:00
priorNoise = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]);
2012-06-03 13:25:05 +08:00
graph.addPrior(1, priorMean, priorNoise); % add directly to graph
2012-01-28 10:51:35 +08:00
%% Add odometry
% general noisemodel for odometry
2012-06-03 13:25:05 +08:00
odometryNoise = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]);
2012-06-04 04:12:12 +08:00
graph.addOdometry(1, 2, gtsamPose2(2.0, 0.0, 0.0 ), odometryNoise);
graph.addOdometry(2, 3, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addOdometry(3, 4, gtsamPose2(2.0, 0.0, pi/2), odometryNoise);
graph.addOdometry(4, 5, gtsamPose2(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
model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]);
graph.addConstraint(5, 2, gtsamPose2(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
initialEstimate = pose2SLAMValues;
initialEstimate.insertPose(1, gtsamPose2(0.5, 0.0, 0.2 ));
initialEstimate.insertPose(2, gtsamPose2(2.3, 0.1,-0.2 ));
initialEstimate.insertPose(3, gtsamPose2(4.1, 0.1, pi/2));
initialEstimate.insertPose(4, gtsamPose2(4.0, 2.0, pi ));
initialEstimate.insertPose(5, gtsamPose2(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);
2012-06-04 04:12:12 +08:00
result.print(sprintf('\nFinal result:\n'));