diff --git a/gtsam/slam/planarSLAM.cpp b/gtsam/slam/planarSLAM.cpp index b5f7b18ef..b490a76cb 100644 --- a/gtsam/slam/planarSLAM.cpp +++ b/gtsam/slam/planarSLAM.cpp @@ -16,7 +16,7 @@ **/ #include -#include +#include // Use planarSLAM namespace for specific SLAM instance namespace planarSLAM { @@ -63,6 +63,11 @@ namespace planarSLAM { } /* ************************************************************************* */ + Values Graph::optimize(const Values& initialEstimate) const { + return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); + } + + /* ************************************************************************* */ } // planarSLAM diff --git a/gtsam/slam/planarSLAM.h b/gtsam/slam/planarSLAM.h index 07e6896e5..818879f26 100644 --- a/gtsam/slam/planarSLAM.h +++ b/gtsam/slam/planarSLAM.h @@ -24,7 +24,6 @@ #include #include #include -#include #include // Use planarSLAM namespace for specific SLAM instance @@ -108,9 +107,7 @@ namespace planarSLAM { void addBearingRange(Index poseKey, Index pointKey, const Rot2& bearing, double range, const SharedNoiseModel& model); /// Optimize - Values optimize(const Values& initialEstimate) { - return LevenbergMarquardtOptimizer(*this, initialEstimate).optimize(); - } + Values optimize(const Values& initialEstimate) const; }; } // planarSLAM