diff --git a/gtsam.h b/gtsam.h index 4bacd0273..054f7a400 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2272,20 +2272,16 @@ typedef gtsam::RangeFactor RangeFactorPosePoint2; typedef gtsam::RangeFactor RangeFactorPosePoint3; typedef gtsam::RangeFactor RangeFactorPose2; typedef gtsam::RangeFactor RangeFactorPose3; - -// Commented out by Frank Dec 2014: not poses! -// If needed, we need a RangeFactor that takes a camera, extracts the pose -// Should be easy with Expressions -//typedef gtsam::RangeFactor RangeFactorCalibratedCameraPoint; -//typedef gtsam::RangeFactor RangeFactorSimpleCameraPoint; -//typedef gtsam::RangeFactor RangeFactorCalibratedCamera; -//typedef gtsam::RangeFactor RangeFactorSimpleCamera; +typedef gtsam::RangeFactor RangeFactorCalibratedCameraPoint; +typedef gtsam::RangeFactor RangeFactorSimpleCameraPoint; +typedef gtsam::RangeFactor RangeFactorCalibratedCamera; +typedef gtsam::RangeFactor RangeFactorSimpleCamera; #include -template +template virtual class BearingFactor : gtsam::NoiseModelFactor { - BearingFactor(size_t key1, size_t key2, const MEASURED& measured, const gtsam::noiseModel::Base* noiseModel); + BearingFactor(size_t key1, size_t key2, const BEARING& measured, const gtsam::noiseModel::Base* noiseModel); // enabling serialization functionality void serialize() const; @@ -2295,9 +2291,9 @@ typedef gtsam::BearingFactor BearingFa #include -template +template virtual class BearingRangeFactor : gtsam::NoiseModelFactor { - BearingRangeFactor(size_t poseKey, size_t pointKey, const MEASURED& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); + BearingRangeFactor(size_t poseKey, size_t pointKey, const BEARING& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); pair measured() const; diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 4d605ef4e..c289f8fb6 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -318,7 +318,7 @@ public: } /// @} - /// @name Transformations and mesaurement functions + /// @name Transformations and measurement functions /// @{ /** @@ -393,5 +393,38 @@ struct traits : public internal::Manifold< CalibratedCamera> { }; +// Define Range functor specializations that are used in RangeFactor +template struct Range; + +template <> +struct Range { + typedef double result_type; + double operator()(const CalibratedCamera& camera, const Point3& point, + OptionalJacobian<1, 6> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) { + return camera.range(point, H1, H2); + } +}; + +template <> +struct Range { + typedef double result_type; + double operator()(const CalibratedCamera& camera, const Pose3& pose, + OptionalJacobian<1, 6> H1 = boost::none, + OptionalJacobian<1, 6> H2 = boost::none) { + return camera.range(pose, H1, H2); + } +}; + +template <> +struct Range { + typedef double result_type; + double operator()(const CalibratedCamera& camera1, + const CalibratedCamera& camera2, + OptionalJacobian<1, 6> H1 = boost::none, + OptionalJacobian<1, 6> H2 = boost::none) { + return camera1.range(camera2, H1, H2); + } +}; } diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 12e9f023b..93c017290 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -263,24 +263,22 @@ public: template double range(const PinholeCamera& camera, OptionalJacobian<1, dimension> Dcamera = boost::none, - boost::optional Dother = boost::none) const { + OptionalJacobian<1, 6 + CalibrationB::dimension> Dother = boost::none) const { Matrix16 Dcamera_, Dother_; double result = this->pose().range(camera.pose(), Dcamera ? &Dcamera_ : 0, Dother ? &Dother_ : 0); if (Dcamera) { - Dcamera->resize(1, 6 + DimK); *Dcamera << Dcamera_, Eigen::Matrix::Zero(); } if (Dother) { - Dother->resize(1, 6 + CalibrationB::dimension); Dother->setZero(); - Dother->block<1, 6>(0, 0) = Dother_; + Dother->template block<1, 6>(0, 0) = Dother_; } return result; } /** - * Calculate range to another camera + * Calculate range to a calibrated camera * @param camera Other camera * @return range (double) */ @@ -314,4 +312,52 @@ struct traits > : public internal::Manifold< PinholeCamera > { }; -} // \ gtsam +// Define Range functor specializations that are used in RangeFactor +template struct Range; + +template +struct Range, Point3> { + typedef double result_type; + typedef PinholeCamera Camera; + double operator()(const Camera& camera, const Point3& point, + OptionalJacobian<1, Camera::dimension> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) { + return camera.range(point, H1, H2); + } +}; + +template +struct Range, Pose3> { + typedef double result_type; + typedef PinholeCamera Camera; + double operator()(const Camera& camera, const Pose3& pose, + OptionalJacobian<1, Camera::dimension> H1 = boost::none, + OptionalJacobian<1, 6> H2 = boost::none) { + return camera.range(pose, H1, H2); + } +}; + +template +struct Range, PinholeCamera > { + typedef double result_type; + typedef PinholeCamera CameraA; + typedef PinholeCamera CameraB; + double operator()(const CameraA& camera1, const CameraB& camera2, + OptionalJacobian<1, CameraA::dimension> H1 = boost::none, + OptionalJacobian<1, CameraB::dimension> H2 = boost::none) { + return camera1.range(camera2, H1, H2); + } +}; + +template +struct Range, CalibratedCamera> { + typedef double result_type; + typedef PinholeCamera Camera; + double operator()(const Camera& camera, const CalibratedCamera& cc, + OptionalJacobian<1, Camera::dimension> H1 = boost::none, + OptionalJacobian<1, 6> H2 = boost::none) { + return camera.range(cc, H1, H2); + } +}; + +} // \ gtsam diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 883e5fb62..e8cf0be7b 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -22,6 +22,7 @@ #pragma once #include +#include #include #include @@ -199,4 +200,19 @@ struct traits : public internal::VectorSpace {}; template<> struct traits : public internal::VectorSpace {}; -} + +template +struct Range; + +template <> +struct Range { + typedef double result_type; + double operator()(const Point3& p, const Point3& q, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) { + return p.distance(q, H1, H2); + } +}; + +} // namespace gtsam + diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index f3cb9e2a1..ab488c65f 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -23,6 +23,7 @@ #include #include #include +#include namespace gtsam { @@ -295,5 +296,51 @@ struct traits : public internal::LieGroup {}; template<> struct traits : public internal::LieGroup {}; +// Define Bearing functor specializations that are used in BearingFactor +template struct Bearing; + +template <> +struct Bearing { + typedef Rot2 result_type; + Rot2 operator()(const Pose2& pose, const Point2& point, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 2> H2 = boost::none) { + return pose.bearing(point, H1, H2); + } +}; + +template <> +struct Bearing { + typedef Rot2 result_type; + Rot2 operator()(const Pose2& pose1, const Pose2& pose2, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) { + return pose1.bearing(pose2, H1, H2); + } +}; + +// Define Range functor specializations that are used in RangeFactor +template struct Range; + +template <> +struct Range { + typedef double result_type; + double operator()(const Pose2& pose, const Point2& point, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 2> H2 = boost::none) { + return pose.range(point, H1, H2); + } +}; + +template <> +struct Range { + typedef double result_type; + double operator()(const Pose2& pose1, const Pose2& pose2, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) { + return pose1.range(pose2, H1, H2); + } +}; + } // namespace gtsam diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 6e36f7ad0..afe953d1d 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -331,11 +331,46 @@ GTSAM_EXPORT boost::optional align(const std::vector& pairs); // For MATLAB wrapper typedef std::vector Pose3Vector; -template<> +template <> struct traits : public internal::LieGroup {}; -template<> +template <> struct traits : public internal::LieGroup {}; +// Define Bearing functor specializations that are used in BearingFactor +template struct Bearing; -} // namespace gtsam +template <> +struct Bearing { + typedef Unit3 result_type; + Unit3 operator()(const Pose3& pose, const Point3& point, + OptionalJacobian<2, 6> H1 = boost::none, + OptionalJacobian<2, 3> H2 = boost::none) { + return pose.bearing(point, H1, H2); + } +}; + +// Define Range functor specializations that are used in RangeFactor +template struct Range; + +template <> +struct Range { + typedef double result_type; + double operator()(const Pose3& pose, const Point3& point, + OptionalJacobian<1, 6> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) { + return pose.range(point, H1, H2); + } +}; + +template <> +struct Range { + typedef double result_type; + double operator()(const Pose3& pose1, const Pose3& pose2, + OptionalJacobian<1, 6> H1 = boost::none, + OptionalJacobian<1, 6> H2 = boost::none) { + return pose1.range(pose2, H1, H2); + } +}; + +} // namespace gtsam diff --git a/gtsam/geometry/concepts.h b/gtsam/geometry/concepts.h index 621f04592..207b48f56 100644 --- a/gtsam/geometry/concepts.h +++ b/gtsam/geometry/concepts.h @@ -59,24 +59,6 @@ private: } }; -/** - * Range measurement concept - * Given a pair of Lie variables, there must exist a function to calculate - * range with derivatives. - */ -template -class RangeMeasurementConcept { -private: - static double checkRangeMeasurement(const V1& x, const V2& p) { - return x.range(p); - } - - static double checkRangeMeasurementDerivatives(const V1& x, const V2& p) { - boost::optional H1, H2; - return x.range(p, H1, H2); - } -}; - } // \namespace gtsam /** @@ -92,7 +74,3 @@ private: #define GTSAM_CONCEPT_POSE_INST(T) template class gtsam::PoseConcept; #define GTSAM_CONCEPT_POSE_TYPE(T) typedef gtsam::PoseConcept _gtsam_PoseConcept##T; -/** Range Measurement macros */ -#define GTSAM_CONCEPT_RANGE_MEASUREMENT_INST(V1,V2) template class gtsam::RangeMeasurementConcept; -#define GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(V1,V2) typedef gtsam::RangeMeasurementConcept _gtsam_RangeMeasurementConcept##V1##V2; - diff --git a/gtsam/sam/BearingFactor.h b/gtsam/sam/BearingFactor.h index 06543e13c..d0d06d30a 100644 --- a/gtsam/sam/BearingFactor.h +++ b/gtsam/sam/BearingFactor.h @@ -11,8 +11,7 @@ /** * @file BearingFactor.h - * @brief Serializable factor induced by a bearing measurement of a point from - *a given pose + * @brief Serializable factor induced by a bearing measurement * @date July 2015 * @author Frank Dellaert **/ @@ -20,17 +19,23 @@ #pragma once #include -#include namespace gtsam { +// forward declaration of Bearing functor, assumed partially specified +template +struct Bearing; + /** * Binary factor for a bearing measurement + * Works for any two types A1,A2 for which the functor Bearing() is + * defined * @addtogroup SAM */ -template -struct BearingFactor : public SerializableExpressionFactor2 { - typedef SerializableExpressionFactor2 Base; +template ::result_type> +struct BearingFactor : public SerializableExpressionFactor2 { + typedef SerializableExpressionFactor2 Base; /// default constructor BearingFactor() {} @@ -44,8 +49,9 @@ struct BearingFactor : public SerializableExpressionFactor2 { // Return measurement expression virtual Expression expression(Key key1, Key key2) const { - return Expression(Expression(key1), &POSE::bearing, - Expression(key2)); + Expression a1_(key1); + Expression a2_(key2); + return Expression(Bearing(), a1_, a2_); } /// print @@ -57,8 +63,8 @@ struct BearingFactor : public SerializableExpressionFactor2 { }; // BearingFactor /// traits -template -struct traits > - : public Testable > {}; +template +struct traits > + : public Testable > {}; } // namespace gtsam diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index 19569e563..6e1a33481 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -11,8 +11,7 @@ /** * @file RangeFactor.h - * @brief Serializable factor induced by a range measurement between two points - *and/or poses + * @brief Serializable factor induced by a range measurement * @date July 2015 * @author Frank Dellaert **/ @@ -20,30 +19,30 @@ #pragma once #include -#include -#include namespace gtsam { +// forward declaration of Range functor, assumed partially specified +template +struct Range; + /** * Binary factor for a range measurement + * Works for any two types A1,A2 for which the functor Range() is defined * @addtogroup SAM */ -template -struct RangeFactor : public SerializableExpressionFactor2 { +template ::result_type> +class RangeFactor : public SerializableExpressionFactor2 { private: typedef RangeFactor This; - typedef SerializableExpressionFactor2 Base; - - // Concept requirements for this factor - GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(A1, A2) + typedef SerializableExpressionFactor2 Base; public: /// default constructor RangeFactor() {} - RangeFactor(Key key1, Key key2, double measured, - const SharedNoiseModel& model) + RangeFactor(Key key1, Key key2, T measured, const SharedNoiseModel& model) : Base(key1, key2, model, measured) { this->initialize(expression(key1, key2)); } @@ -55,10 +54,10 @@ struct RangeFactor : public SerializableExpressionFactor2 { } // Return measurement expression - virtual Expression expression(Key key1, Key key2) const { - Expression t1_(key1); - Expression t2_(key2); - return Expression(t1_, &A1::range, t2_); + virtual Expression expression(Key key1, Key key2) const { + Expression a1_(key1); + Expression a2_(key2); + return Expression(Range(), a1_, a2_); } /// print @@ -70,30 +69,29 @@ struct RangeFactor : public SerializableExpressionFactor2 { }; // \ RangeFactor /// traits -template -struct traits > : public Testable > {}; +template +struct traits > + : public Testable > {}; /** * Binary factor for a range measurement, with a transform applied * @addtogroup SAM */ -template +template ::result_type> class RangeFactorWithTransform - : public SerializableExpressionFactor2 { + : public SerializableExpressionFactor2 { private: typedef RangeFactorWithTransform This; - typedef SerializableExpressionFactor2 Base; + typedef SerializableExpressionFactor2 Base; A1 body_T_sensor_; ///< The pose of the sensor in the body frame - // Concept requirements for this factor - GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(A1, A2) - public: //// Default constructor RangeFactorWithTransform() {} - RangeFactorWithTransform(Key key1, Key key2, double measured, + RangeFactorWithTransform(Key key1, Key key2, T measured, const SharedNoiseModel& model, const A1& body_T_sensor) : Base(key1, key2, model, measured), body_T_sensor_(body_T_sensor) { @@ -109,13 +107,13 @@ class RangeFactorWithTransform } // Return measurement expression - virtual Expression expression(Key key1, Key key2) const { + virtual Expression expression(Key key1, Key key2) const { Expression body_T_sensor__(body_T_sensor_); Expression nav_T_body_(key1); Expression nav_T_sensor_(traits::Compose, nav_T_body_, body_T_sensor__); - Expression t2_(key2); - return Expression(nav_T_sensor_, &A1::range, t2_); + Expression a2_(key2); + return Expression(Range(), nav_T_sensor_, a2_); } /** print contents */ @@ -128,8 +126,8 @@ class RangeFactorWithTransform private: /** Serialization function */ - friend class boost::serialization::access; - template + friend typename boost::serialization::access; + template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); @@ -138,8 +136,8 @@ class RangeFactorWithTransform }; // \ RangeFactorWithTransform /// traits -template -struct traits > - : public Testable > {}; +template +struct traits > + : public Testable > {}; } // \ namespace gtsam diff --git a/gtsam/sam/tests/testBearingFactor.cpp b/gtsam/sam/tests/testBearingFactor.cpp index f351ecdbf..d92bbdfe8 100644 --- a/gtsam/sam/tests/testBearingFactor.cpp +++ b/gtsam/sam/tests/testBearingFactor.cpp @@ -32,12 +32,12 @@ using namespace gtsam; Key poseKey(1); Key pointKey(2); -typedef BearingFactor BearingFactor2D; +typedef BearingFactor BearingFactor2D; double measurement2D(10.0); static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(1, 0.5)); BearingFactor2D factor2D(poseKey, pointKey, measurement2D, model2D); -typedef BearingFactor BearingFactor3D; +typedef BearingFactor BearingFactor3D; Unit3 measurement3D = Pose3().bearing(Point3(1, 0, 0)); // has to match values! static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5)); BearingFactor3D factor3D(poseKey, pointKey, measurement3D, model3D); diff --git a/gtsam/sam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp index 39cdaa2ab..88595b32c 100644 --- a/gtsam/sam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -344,6 +344,58 @@ TEST( RangeFactor, Jacobian3DWithTransform ) { CHECK(assert_equal(H2Expected, H2Actual, 1e-9)); } +/* ************************************************************************* */ +// Do a test with Point3 +TEST(RangeFactor, Point3) { + // Create a factor + Key poseKey(1); + Key pointKey(2); + double measurement(10.0); + RangeFactor factor(poseKey, pointKey, measurement, model); + + // Set the linearization point + Point3 pose(1.0, 2.0, 00); + Point3 point(-4.0, 11.0, 0); + + // The expected error is ||(5.0, 9.0)|| - 10.0 = 0.295630141 meter / UnitCovariance + Vector expectedError = (Vector(1) << 0.295630141).finished(); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9)); +} + +/* ************************************************************************* */ +// Do a test with non GTSAM types + +namespace gtsam{ +template <> +struct Range { + typedef double result_type; + double operator()(const Vector3& v1, const Vector3& v2, + OptionalJacobian<1, 3> H1, OptionalJacobian<1, 3> H2) { + return (v2 - v1).norm(); + } +}; +} + +TEST(RangeFactor, NonGTSAM) { + // Create a factor + Key poseKey(1); + Key pointKey(2); + double measurement(10.0); + RangeFactor factor(poseKey, pointKey, measurement, model); + + // Set the linearization point + Vector3 pose(1.0, 2.0, 00); + Vector3 point(-4.0, 11.0, 0); + + // The expected error is ||(5.0, 9.0)|| - 10.0 = 0.295630141 meter / UnitCovariance + Vector expectedError = (Vector(1) << 0.295630141).finished(); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 1b51224d2..7503a8bb1 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -47,7 +47,6 @@ namespace gtsam { /** concept check by type */ GTSAM_CONCEPT_TESTABLE_TYPE(Rot) - GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(Pose, Point) GTSAM_CONCEPT_POSE_TYPE(Pose) public: diff --git a/gtsam_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index 78bd1fe6f..a6bc6006a 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -170,4 +170,17 @@ private: template<> struct traits : public internal::LieGroup {}; +// Define Range functor specializations that are used in RangeFactor +template struct Range; + +template <> +struct Range { + typedef double result_type; + double operator()(const PoseRTV& pose1, const PoseRTV& pose2, + OptionalJacobian<1, 9> H1 = boost::none, + OptionalJacobian<1, 9> H2 = boost::none) { + return pose1.range(pose2, H1, H2); + } +}; + } // \namespace gtsam