From 08c72e2a8dc7888e8d8c3e4aa68f2dfbc80276b0 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Mon, 30 Jul 2012 14:59:18 +0000 Subject: [PATCH] Updated Pose2SLAMExample_graph to remove SLAM namespaces --- examples/Pose2SLAMExample_graph.cpp | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/examples/Pose2SLAMExample_graph.cpp b/examples/Pose2SLAMExample_graph.cpp index d27e184d8..cc873eb08 100644 --- a/examples/Pose2SLAMExample_graph.cpp +++ b/examples/Pose2SLAMExample_graph.cpp @@ -17,32 +17,35 @@ */ #include -#include +#include #include +#include +#include +#include +#include #include #include using namespace std; using namespace gtsam; -using namespace gtsam::noiseModel; int main(int argc, char** argv) { // Read File and create graph and initial estimate // we are in build/examples, data is in examples/Data - pose2SLAM::Graph::shared_ptr graph ; - pose2SLAM::Values::shared_ptr initial; - SharedDiagonal model = Diagonal::Sigmas(Vector_(3, 0.05, 0.05, 5.0*M_PI/180.0)); + NonlinearFactorGraph::shared_ptr graph ; + Values::shared_ptr initial; + SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.05, 0.05, 5.0*M_PI/180.0)); boost::tie(graph,initial) = load2D("../../examples/Data/w100-odom.graph",model); initial->print("Initial estimate:\n"); // Add a Gaussian prior on first poses Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin - SharedDiagonal priorNoise = Diagonal::Sigmas(Vector_(3, 0.01, 0.01, 0.01)); - graph->addPosePrior(0, priorMean, priorNoise); + SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.01, 0.01, 0.01)); + graph->add(PriorFactor(0, priorMean, priorNoise)); // Single Step Optimization using Levenberg-Marquardt - pose2SLAM::Values result = graph->optimize(*initial); + Values result = LevenbergMarquardtOptimizer(*graph, *initial).optimize(); result.print("\nFinal result:\n"); // Plot the covariance of the last pose