diff --git a/gtsam/sfm/ShonanAveraging.cpp b/gtsam/sfm/ShonanAveraging.cpp index bc3783a27..8fed0538d 100644 --- a/gtsam/sfm/ShonanAveraging.cpp +++ b/gtsam/sfm/ShonanAveraging.cpp @@ -812,7 +812,7 @@ std::pair ShonanAveraging::run(const Values &initialEstimate, return std::make_pair(SO3Values, 0); } - // Check certificate of global optimzality + // Check certificate of global optimality Vector minEigenVector; double minEigenValue = computeMinEigenValue(Qstar, &minEigenVector); if (minEigenValue > parameters_.optimalityThreshold) { @@ -837,17 +837,13 @@ template class ShonanAveraging<2>; ShonanAveraging2::ShonanAveraging2(const Measurements &measurements, const Parameters ¶meters) - : ShonanAveraging<2>(parameters.useHuber - ? makeNoiseModelRobust(measurements) - : measurements, + : ShonanAveraging<2>(maybeRobust(measurements, parameters.getUseHuber()), parameters) {} ShonanAveraging2::ShonanAveraging2(string g2oFile, const Parameters ¶meters) - : ShonanAveraging<2>( - parameters.useHuber - ? makeNoiseModelRobust(parseMeasurements(g2oFile)) - : parseMeasurements(g2oFile), - parameters) {} + : ShonanAveraging<2>(maybeRobust(parseMeasurements(g2oFile), + parameters.getUseHuber()), + parameters) {} /* ************************************************************************* */ // Explicit instantiation for d=3 @@ -855,15 +851,13 @@ template class ShonanAveraging<3>; ShonanAveraging3::ShonanAveraging3(const Measurements &measurements, const Parameters ¶meters) - : ShonanAveraging<3>(parameters.useHuber? - makeNoiseModelRobust(measurements) : measurements, parameters) {} + : ShonanAveraging<3>(maybeRobust(measurements, parameters.getUseHuber()), + parameters) {} ShonanAveraging3::ShonanAveraging3(string g2oFile, const Parameters ¶meters) - : ShonanAveraging<3>( - parameters.useHuber - ? makeNoiseModelRobust(parseMeasurements(g2oFile)) - : parseMeasurements(g2oFile), - parameters) {} + : ShonanAveraging<3>(maybeRobust(parseMeasurements(g2oFile), + parameters.getUseHuber()), + parameters) {} // TODO(frank): Deprecate after we land pybind wrapper @@ -895,11 +889,9 @@ static ShonanAveraging3::Measurements extractRot3Measurements( ShonanAveraging3::ShonanAveraging3(const BetweenFactorPose3s &factors, const Parameters ¶meters) - : ShonanAveraging<3>( - parameters.useHuber - ? makeNoiseModelRobust(extractRot3Measurements(factors)) - : extractRot3Measurements(factors), - parameters) {} + : ShonanAveraging<3>(maybeRobust(extractRot3Measurements(factors), + parameters.getUseHuber()), + parameters) {} /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/sfm/ShonanAveraging.h b/gtsam/sfm/ShonanAveraging.h index ad8d2944a..48d873a1a 100644 --- a/gtsam/sfm/ShonanAveraging.h +++ b/gtsam/sfm/ShonanAveraging.h @@ -389,6 +389,22 @@ class GTSAM_EXPORT ShonanAveraging { std::pair run(const Values &initialEstimate, size_t pMin = d, size_t pMax = 10) const; /// @} + + /** + * Helper function to convert measurements to robust noise model + * if flag is set. + * + * @tparam T the type of measurement, e.g. Rot3. + * @param measurements vector of BinaryMeasurements of type T. + * @param useRobustModel flag indicating whether use robust noise model + * instead. + */ + template + inline std::vector> maybeRobust( + const std::vector> &measurements, + bool useRobustModel = false) const { + return useRobustModel ? makeNoiseModelRobust(measurements) : measurements; + } }; // Subclasses for d=2 and d=3 that explicitly instantiate, as well as provide a