Typo fixed

release/4.3a0
Luca Carlone 2013-09-27 16:06:36 +00:00
parent e10a0a0650
commit 7560a1f6e3
1 changed files with 2 additions and 3 deletions

View File

@ -35,11 +35,10 @@
#include <gtsam/nonlinear/NonlinearFactorGraph.h> #include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
// We will use a non-liear solver to batch-inituialize from the first 150 frames // We will use a non-linear solver to batch-initialize from the first 150 frames
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h> #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/nonlinear/GaussNewtonOptimizer.h> #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
// In GTSAM, measurement functions are represented as 'factors'. Several common factors // In GTSAM, measurement functions are represented as 'factors'. Several common factors
// have been provided with the library for solving robotics SLAM problems. // have been provided with the library for solving robotics SLAM problems.
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>
@ -333,7 +332,7 @@ int main(int argc, char** argv) {
unsigned int maxNumPoses = 45400; //3541 unsigned int maxNumPoses = 45400; //3541
// Set to true to use SmartProjectionFactor. Otherwise GenericProjectionFactor will be used // Set to true to use SmartProjectionFactor. Otherwise GenericProjectionFactor will be used
bool useSmartProjectionFactor = false; bool useSmartProjectionFactor = true;
bool useTriangulation = true; bool useTriangulation = true;
bool useLM = true; bool useLM = true;