diff --git a/examples/PlanarSLAMExample.cpp b/examples/PlanarSLAMExample.cpp index 84f9be3a1..a716f9cd8 100644 --- a/examples/PlanarSLAMExample.cpp +++ b/examples/PlanarSLAMExample.cpp @@ -42,7 +42,7 @@ // Also, we will initialize the robot at the origin using a Prior factor. #include #include -#include +#include // When the factors are created, we will add them to a Factor Graph. As the factors we are using // are nonlinear factors, we will need a Nonlinear Factor Graph. diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index 068846884..2000b348b 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -32,7 +32,7 @@ */ #include -#include +#include #include #include #include diff --git a/gtsam.h b/gtsam.h index 054f7a400..d874467fc 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2290,7 +2290,7 @@ virtual class BearingFactor : gtsam::NoiseModelFactor { typedef gtsam::BearingFactor BearingFactor2D; -#include +#include template virtual class BearingRangeFactor : gtsam::NoiseModelFactor { BearingRangeFactor(size_t poseKey, size_t pointKey, const BEARING& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h new file mode 100644 index 000000000..6ef1d7e55 --- /dev/null +++ b/gtsam/sam/BearingRangeFactor.h @@ -0,0 +1,148 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file BearingRangeFactor.h + * @date Apr 1, 2010 + * @author Kai Ni + * @brief a single factor contains both the bearing and the range to prevent + * handle to pair bearing and range factors + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +// forward declaration of Bearing functor, assumed partially specified +template +struct Bearing; + +// forward declaration of Range functor, assumed partially specified +template +struct Range; + +template +struct BearingRange : public ProductManifold { + BearingRange() {} + BearingRange(const ProductManifold& br) : ProductManifold(br) {} + BearingRange(const B& b, const R& r) : ProductManifold(b, r) {} + + private: + /// Serialization function + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp("bearing", this->first); + ar& boost::serialization::make_nvp("range", this->second); + } + + friend class boost::serialization::access; +}; + +template +struct traits > + : internal::ManifoldTraits > { + static void Print(const BearingRange& m, const std::string& str = "") { + traits::Print(m.first, str); + traits::Print(m.second, str); + } + static bool Equals(const BearingRange& m1, const BearingRange& m2, + double tol = 1e-8) { + return traits::Equals(m1.first, m2.first, tol) && + traits::Equals(m1.second, m2.second, tol); + } +}; + +/** + * Binary factor for a bearing/range measurement + * @addtogroup SLAM + */ +template ::result_type, + typename R = typename Range::result_type> +class BearingRangeFactor + : public SerializableExpressionFactor2, A1, A2> { + public: + typedef BearingRange T; + typedef SerializableExpressionFactor2 Base; + typedef BearingRangeFactor This; + typedef boost::shared_ptr shared_ptr; + + private: + /** concept check by type */ + BOOST_CONCEPT_ASSERT((IsTestable)); + BOOST_CONCEPT_ASSERT((IsTestable)); + + public: + /// default constructor + BearingRangeFactor() {} + + /// primary constructor + BearingRangeFactor(Key key1, Key key2, const B& measuredBearing, + const R measuredRange, const SharedNoiseModel& model) + : Base(key1, key2, model, T(measuredBearing, measuredRange)) { + this->initialize(expression(key1, key2)); + } + + virtual ~BearingRangeFactor() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } + + // Return measurement expression + virtual Expression expression(Key key1, Key key2) const { + Expression a1_(key1); + Expression a2_(key2); + return Expression(This::Predict, a1_, a2_); + } + + /** Print */ + virtual void print( + const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "BearingRangeFactor(" << keyFormatter(this->keys_[0]) + << "," << keyFormatter(this->keys_[1]) << ")\n"; + traits::Print(this->measured_.first, "measured bearing: "); + traits::Print(this->measured_.second, "measured range: "); + this->noiseModel_->print("noise model:\n"); + } + + /// Prediction function that stacks measurements + static T Predict(const A1& pose, const A2& point, + typename MakeOptionalJacobian::type H1, + typename MakeOptionalJacobian::type H2) { + typename MakeJacobian::type HB1; + typename MakeJacobian::type HB2; + typename MakeJacobian::type HR1; + typename MakeJacobian::type HR2; + + B b = Bearing()(pose, point, H1 ? &HB1 : 0, H2 ? &HB2 : 0); + R r = Range()(pose, point, H1 ? &HR1 : 0, H2 ? &HR2 : 0); + + if (H1) *H1 << HB1, HR1; + if (H2) *H2 << HB2, HR2; + return T(b, r); + } + +}; // BearingRangeFactor + +/// traits +template +struct traits > + : public Testable > {}; + +} // namespace gtsam diff --git a/gtsam/sam/tests/testBearingRangeFactor.cpp b/gtsam/sam/tests/testBearingRangeFactor.cpp new file mode 100644 index 000000000..8f12988b4 --- /dev/null +++ b/gtsam/sam/tests/testBearingRangeFactor.cpp @@ -0,0 +1,109 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testBearingRangeFactor.cpp + * @brief Unit tests for BearingRangeFactor Class + * @author Frank Dellaert + * @date July 2015 + */ + +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; +using namespace serializationTestHelpers; + +Key poseKey(1); +Key pointKey(2); + +typedef BearingRangeFactor BearingRangeFactor2D; +BearingRangeFactor2D::T measurement2D(1, 2); +static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(2, 0.5)); +BearingRangeFactor2D factor2D(poseKey, pointKey, 1, 2, model2D); + +typedef BearingRangeFactor BearingRangeFactor3D; +BearingRangeFactor3D::T measurement3D(Pose3().bearing(Point3(1, 0, 0)), 0); +static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(3, 0.5)); +BearingRangeFactor3D factor3D(poseKey, pointKey, + Pose3().bearing(Point3(1, 0, 0)), 1, model3D); + +/* ************************************************************************* */ +// Export Noisemodels +// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html +BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic); + +/* ************************************************************************* */ +TEST(BearingRangeFactor, Serialization2D) { + EXPECT(equalsObj(factor2D)); + EXPECT(equalsXML(factor2D)); + EXPECT(equalsBinary(factor2D)); +} + +/* ************************************************************************* */ +TEST(BearingRangeFactor, 2D) { + // Serialize the factor + std::string serialized = serializeXML(factor2D); + + // And de-serialize it + BearingRangeFactor2D factor; + deserializeXML(serialized, factor); + + // Set the linearization point + Values values; + values.insert(poseKey, Pose2(1.0, 2.0, 0.57)); + values.insert(pointKey, Point2(-4.0, 11.0)); + + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), + values, 1e-7, 1e-5); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +TEST(BearingRangeFactor, Serialization3D) { + EXPECT(equalsObj(factor3D)); + EXPECT(equalsXML(factor3D)); + EXPECT(equalsBinary(factor3D)); +} + +/* ************************************************************************* */ +TEST(BearingRangeFactor, 3D) { + // Serialize the factor + std::string serialized = serializeXML(factor3D); + + // And de-serialize it + BearingRangeFactor3D factor; + deserializeXML(serialized, factor); + + // Set the linearization point + Values values; + values.insert(poseKey, Pose3()); + values.insert(pointKey, Point3(1, 0, 0)); + + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), + values, 1e-7, 1e-5); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 131a08f4b..901860015 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -9,130 +9,13 @@ * -------------------------------------------------------------------------- */ -/** - * @file BearingRangeFactor.h - * @date Apr 1, 2010 - * @author Kai Ni - * @brief a single factor contains both the bearing and the range to prevent - * handle to pair bearing and range factors - */ - #pragma once -#include -#include -#include +#ifdef _MSC_VER +#pragma message( \ + "BearingRangeFactor is now an ExpressionFactor in SAM directory") +#else +#warning "BearingRangeFactor is now an ExpressionFactor in SAM directory" +#endif -#include - -namespace gtsam { - -// forward declaration of Bearing functor, assumed partially specified -template -struct Bearing; - -// forward declaration of Range functor, assumed partially specified -template -struct Range; - -/** - * Binary factor for a bearing/range measurement - * @addtogroup SLAM - */ -template ::result_type, - typename RANGE = typename Range::result_type> -class BearingRangeFactor : public NoiseModelFactor2 { - public: - typedef BearingRangeFactor This; - typedef NoiseModelFactor2 Base; - typedef boost::shared_ptr shared_ptr; - - private: - // the measurement - BEARING measuredBearing_; - RANGE measuredRange_; - - /** concept check by type */ - BOOST_CONCEPT_ASSERT((IsTestable)); - BOOST_CONCEPT_ASSERT((IsTestable)); - - public: - BearingRangeFactor() {} /* Default constructor */ - BearingRangeFactor(Key poseKey, Key pointKey, const BEARING& measuredBearing, - const RANGE measuredRange, const SharedNoiseModel& model) - : Base(model, poseKey, pointKey), - measuredBearing_(measuredBearing), - measuredRange_(measuredRange) {} - - virtual ~BearingRangeFactor() {} - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); - } - - /** Print */ - virtual void print( - const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "BearingRangeFactor(" << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << ")\n"; - measuredBearing_.print("measured bearing: "); - std::cout << "measured range: " << measuredRange_ << std::endl; - this->noiseModel_->print("noise model:\n"); - } - - /** equals */ - virtual bool equals(const NonlinearFactor& expected, RANGE tol = 1e-9) const { - const This* e = dynamic_cast(&expected); - return e != NULL && Base::equals(*e, tol) && - fabs(this->measuredRange_ - e->measuredRange_) < tol && - this->measuredBearing_.equals(e->measuredBearing_, tol); - } - - /** h(x)-z -> between(z,h(x)) for BEARING manifold */ - Vector evaluateError(const A1& pose, const A2& point, - boost::optional H1, - boost::optional H2) const { - typename MakeJacobian::type HB1; - typename MakeJacobian::type HB2; - typename MakeJacobian::type HR1; - typename MakeJacobian::type HR2; - - BEARING y1 = Bearing()(pose, point, H1 ? &HB1 : 0, H2 ? &HB2 : 0); - Vector e1 = traits::Logmap(traits::Between(measuredBearing_,y1)); - - RANGE y2 = Range()(pose, point, H1 ? &HR1 : 0, H2 ? &HR2 : 0); - Vector e2 = traits::Logmap(traits::Between(measuredRange_, y2)); - - if (H1) { - H1->resize(HB1.RowsAtCompileTime + HR1.RowsAtCompileTime, HB1.ColsAtCompileTime); - *H1 << HB1, HR1; - } - if (H2) { - H2->resize(HB2.RowsAtCompileTime + HR2.RowsAtCompileTime, HB2.ColsAtCompileTime); - *H2 << HB2, HR2; - } - return concatVectors(2, &e1, &e2); - } - - /** return the measured */ - const std::pair measured() const { - return std::make_pair(measuredBearing_, measuredRange_); - } - - private: - /** Serialization function */ - friend typename boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "NoiseModelFactor2", boost::serialization::base_object(*this)); - ar& BOOST_SERIALIZATION_NVP(measuredBearing_); - ar& BOOST_SERIALIZATION_NVP(measuredRange_); - } -}; // BearingRangeFactor - -} // namespace gtsam +#include diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 70b6eb622..04234bacc 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -15,7 +15,7 @@ * @brief utility functions for loading datasets */ -#include +#include #include #include #include diff --git a/gtsam_unstable/slam/serialization.cpp b/gtsam_unstable/slam/serialization.cpp index 194fc6e87..7928a2aac 100644 --- a/gtsam_unstable/slam/serialization.cpp +++ b/gtsam_unstable/slam/serialization.cpp @@ -11,7 +11,7 @@ #include //#include -#include +#include #include //#include #include diff --git a/gtsam_unstable/slam/tests/testSerialization.cpp b/gtsam_unstable/slam/tests/testSerialization.cpp index a5e09515c..1d8b30850 100644 --- a/gtsam_unstable/slam/tests/testSerialization.cpp +++ b/gtsam_unstable/slam/tests/testSerialization.cpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index 38b5057a6..58c718726 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/tests/testGaussianJunctionTreeB.cpp b/tests/testGaussianJunctionTreeB.cpp index 98adfc1dc..e877e5a9d 100644 --- a/tests/testGaussianJunctionTreeB.cpp +++ b/tests/testGaussianJunctionTreeB.cpp @@ -16,7 +16,7 @@ */ #include -#include +#include #include #include #include diff --git a/tests/testMarginals.cpp b/tests/testMarginals.cpp index bd202e991..392b84deb 100644 --- a/tests/testMarginals.cpp +++ b/tests/testMarginals.cpp @@ -31,7 +31,7 @@ // add in headers for specific factors #include #include -#include +#include #include diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index e9e266bb3..3c49d54af 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -6,7 +6,7 @@ #include #include -#include +#include #include #include #include diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSLAM.cpp index 08017100f..33453d7d3 100644 --- a/tests/testSerializationSLAM.cpp +++ b/tests/testSerializationSLAM.cpp @@ -22,7 +22,7 @@ #include //#include -#include +#include #include //#include #include diff --git a/timing/timeIncremental.cpp b/timing/timeIncremental.cpp index d82ef9442..b5dd37516 100644 --- a/timing/timeIncremental.cpp +++ b/timing/timeIncremental.cpp @@ -17,7 +17,7 @@ #include #include #include -#include +#include #include #include #include