const correctness, moved optimizer to cpp

release/4.3a0
Frank Dellaert 2012-05-20 17:31:55 +00:00
parent 272734fab7
commit fd80a9da90
2 changed files with 7 additions and 5 deletions

View File

@ -16,7 +16,7 @@
**/
#include <gtsam/slam/planarSLAM.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
// 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

View File

@ -24,7 +24,6 @@
#include <gtsam/slam/BearingRangeFactor.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/geometry/Pose2.h>
// 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