diff --git a/matlab/gtsam_examples/PlanarSLAMExample.m b/matlab/gtsam_examples/PlanarSLAMExample.m index 1dc6ba41c..ef1516017 100644 --- a/matlab/gtsam_examples/PlanarSLAMExample.m +++ b/matlab/gtsam_examples/PlanarSLAMExample.m @@ -31,7 +31,7 @@ graph = NonlinearFactorGraph; %% Add prior priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); -graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph +graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); %% Add odometry odometry = Pose2(2.0, 0.0, 0.0); @@ -42,7 +42,7 @@ 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(4+4), brNoise)); +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)); @@ -69,7 +69,7 @@ cla;hold on marginals = Marginals(graph, result); plot2DTrajectory(result, [], marginals); -plot2DPoints(result, [], marginals); +plot2DPoints(result, 'b', marginals); plot([result.at(i1).x; result.at(j1).x],[result.at(i1).y; result.at(j1).y], 'c-'); plot([result.at(i2).x; result.at(j1).x],[result.at(i2).y; result.at(j1).y], 'c-'); diff --git a/matlab/gtsam_examples/Pose2SLAMExample_graph.m b/matlab/gtsam_examples/Pose2SLAMExample_graph.m index b48485573..eb1b03950 100644 --- a/matlab/gtsam_examples/Pose2SLAMExample_graph.m +++ b/matlab/gtsam_examples/Pose2SLAMExample_graph.m @@ -17,11 +17,7 @@ datafile = findExampleDataFile('w100-odom.graph'); %% Initialize graph, initial estimate, and odometry noise model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 5*pi/180]); -maxID = 0; -addNoise = false; -smart = true; -[graph,initial] = load2D(datafile, model, maxID, addNoise, smart); -initial.print(sprintf('Initial estimate:\n')); +[graph,initial] = load2D(datafile, model); %% Add a Gaussian prior on pose x_1 priorMean = Pose2(0, 0, 0); % prior mean is at origin @@ -34,9 +30,10 @@ plot2DTrajectory(initial, 'g-*'); axis equal %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd optimizer = LevenbergMarquardtOptimizer(graph, initial); +tic result = optimizer.optimizeSafely; +toc hold on; plot2DTrajectory(result, 'b-*'); -result.print(sprintf('\nFinal result:\n')); %% Plot Covariance Ellipses marginals = Marginals(graph, result); @@ -48,4 +45,4 @@ for i=1:result.size()-1 end view(2) axis tight; axis equal; -fprintf(1,'%.5f %.5f %.5f\n',P{99}) \ No newline at end of file +% fprintf(1,'%.5f %.5f %.5f\n',P{99}) \ No newline at end of file