diff --git a/gtsam_unstable/examples/SmartProjectionFactorExample_kitti_nonbatch.cpp b/gtsam_unstable/examples/SmartProjectionFactorExample_kitti_nonbatch.cpp index 9d6e5ab01..94e1e0639 100644 --- a/gtsam_unstable/examples/SmartProjectionFactorExample_kitti_nonbatch.cpp +++ b/gtsam_unstable/examples/SmartProjectionFactorExample_kitti_nonbatch.cpp @@ -35,11 +35,10 @@ #include #include -// 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 #include - // In GTSAM, measurement functions are represented as 'factors'. Several common factors // have been provided with the library for solving robotics SLAM problems. #include @@ -333,7 +332,7 @@ int main(int argc, char** argv) { unsigned int maxNumPoses = 45400; //3541 // Set to true to use SmartProjectionFactor. Otherwise GenericProjectionFactor will be used - bool useSmartProjectionFactor = false; + bool useSmartProjectionFactor = true; bool useTriangulation = true; bool useLM = true;