diff --git a/examples/PlanarSLAMExample_easy.cpp b/examples/PlanarSLAMExample_easy.cpp index 44200af39..f840c443d 100644 --- a/examples/PlanarSLAMExample_easy.cpp +++ b/examples/PlanarSLAMExample_easy.cpp @@ -86,10 +86,8 @@ int main(int argc, char** argv) { initialEstimate.print("initial estimate"); // optimize using Levenberg-Marquardt optimization with an ordering from colamd -// Values result = optimize(graph, initialEstimate); -// result.print("final result"); - boost::shared_ptr result = graph.optimize(initialEstimate); - result->print("final result"); + Values result = optimize(graph, initialEstimate); + result.print("final result"); return 0; } diff --git a/examples/matlab/PlanarSLAMExample_easy.m b/examples/matlab/PlanarSLAMExample_easy.m index 8d9c250b0..d0cb9d6af 100644 --- a/examples/matlab/PlanarSLAMExample_easy.m +++ b/examples/matlab/PlanarSLAMExample_easy.m @@ -71,5 +71,5 @@ initialEstimate.insertPoint(l2, Landmark2(4.1, 1.8)); initialEstimate.print('initial estimate'); %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd -result = graph.optimize(initialEstimate); +result = graph.optimize_(initialEstimate); result.print('final result'); diff --git a/gtsam/slam/PlanarSLAMValues.h b/gtsam/slam/PlanarSLAMValues.h index 318cc4e04..d174229fd 100644 --- a/gtsam/slam/PlanarSLAMValues.h +++ b/gtsam/slam/PlanarSLAMValues.h @@ -11,7 +11,7 @@ /** * @file PlanarSLAMValues.h - * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB + * @brief Convenience for MATLAB wrapper, which does not allow for identically named methods * @author Frank Dellaert */ diff --git a/gtsam/slam/planarSLAM.cpp b/gtsam/slam/planarSLAM.cpp index 5b1fc033a..e189928f4 100644 --- a/gtsam/slam/planarSLAM.cpp +++ b/gtsam/slam/planarSLAM.cpp @@ -26,7 +26,6 @@ namespace gtsam { using namespace planarSLAM; INSTANTIATE_LIE_VALUES(PointKey) - INSTANTIATE_LIE_VALUES(PoseKey) INSTANTIATE_TUPLE_VALUES2(PoseValues, PointValues) INSTANTIATE_NONLINEAR_FACTOR_GRAPH(Values) INSTANTIATE_NONLINEAR_OPTIMIZER(Graph, Values) diff --git a/gtsam/slam/planarSLAM.h b/gtsam/slam/planarSLAM.h index 840c7adae..024b2f8ff 100644 --- a/gtsam/slam/planarSLAM.h +++ b/gtsam/slam/planarSLAM.h @@ -68,11 +68,11 @@ namespace gtsam { /// insert a pose void insertPose(int key, const Pose2& pose) {insert(PoseKey(key), pose); } - /// insert a point + /// insert a point void insertPoint(int key, const Point2& point) {insert(PointKey(key), point); } }; - /** + /** * List of typedefs for factors */ @@ -120,12 +120,13 @@ namespace gtsam { void addBearingRange(const PoseKey& i, const PointKey& j, const Rot2& z1, double z2, const SharedNoiseModel& model); - /// Optimize, mostly here for MATLAB - boost::shared_ptr optimize(const Values& initialEstimate) { + /// Optimize_ for MATLAB + boost::shared_ptr optimize_(const Values& initialEstimate) { typedef NonlinearOptimizer Optimizer; -// NonlinearOptimizationParameters::LAMBDA boost::shared_ptr result( - new Values(*Optimizer::optimizeGN(*this, initialEstimate))); + new Values( + *Optimizer::optimizeLM(*this, initialEstimate, + NonlinearOptimizationParameters::LAMBDA))); return result; } };