diff --git a/gtsam/nonlinear/GncParams.h b/gtsam/nonlinear/GncParams.h index 10ac80663..b1237b790 100644 --- a/gtsam/nonlinear/GncParams.h +++ b/gtsam/nonlinear/GncParams.h @@ -73,13 +73,12 @@ class GncParams { double weightsTol = 1e-4; ///< If the weights are within weightsTol from being binary, stop iterating (only for TLS) Verbosity verbosity = SILENT; ///< Verbosity level - //TODO(Varun) replace IndexVector with vector once pybind11/stl.h is globally enabled. - /// Use IndexVector for inliers and outliers since it is fast + wrapping + /// Use IndexVector for inliers and outliers since it is fast using IndexVector = FastVector; ///< Slots in the factor graph corresponding to measurements that we know are inliers - IndexVector knownInliers = IndexVector(); + IndexVector knownInliers; ///< Slots in the factor graph corresponding to measurements that we know are outliers - IndexVector knownOutliers = IndexVector(); + IndexVector knownOutliers; /// Set the robust loss function to be used in GNC (chosen among the ones in GncLossType). void setLossType(const GncLossType type) { diff --git a/tests/testGncOptimizer.cpp b/tests/testGncOptimizer.cpp index 5424a5744..4e0ebf516 100644 --- a/tests/testGncOptimizer.cpp +++ b/tests/testGncOptimizer.cpp @@ -750,7 +750,8 @@ TEST(GncOptimizer, optimizeSmallPoseGraph) { // add a few outliers SharedDiagonal betweenNoise = noiseModel::Diagonal::Sigmas( Vector3(0.1, 0.1, 0.01)); - graph->push_back(BetweenFactor(90, 50, Pose2(), betweenNoise)); // some arbitrary and incorrect between factor + // some arbitrary and incorrect between factor + graph->push_back(BetweenFactor(90, 50, Pose2(), betweenNoise)); /// get expected values by optimizing outlier-free graph Values expectedWithOutliers = LevenbergMarquardtOptimizer(*graph, *initial) @@ -759,9 +760,9 @@ TEST(GncOptimizer, optimizeSmallPoseGraph) { // CHECK(assert_equal(expected, expectedWithOutliers, 1e-3)); // GNC - // Note: in difficult instances, we set the odometry measurements to be - // inliers, but this problem is simple enought to succeed even without that - // assumption GncParams::IndexVector knownInliers; + // NOTE: in difficult instances, we set the odometry measurements to be + // inliers, but this problem is simple enough to succeed even without that + // assumption. GncParams gncParams; auto gnc = GncOptimizer>(*graph, *initial, gncParams);