diff --git a/gtsam.h b/gtsam.h index d874467fc..1ddae3f48 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1,4 +1,5 @@ /** + * GTSAM Wrap Module Definition * * These are the current classes available through the matlab toolbox interface, @@ -2289,19 +2290,18 @@ virtual class BearingFactor : gtsam::NoiseModelFactor { typedef gtsam::BearingFactor BearingFactor2D; - #include -template +template virtual class BearingRangeFactor : gtsam::NoiseModelFactor { - BearingRangeFactor(size_t poseKey, size_t pointKey, const BEARING& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); - - pair measured() const; + BearingRangeFactor(size_t poseKey, size_t pointKey, + const BEARING& measuredBearing, const RANGE& measuredRange, + const gtsam::noiseModel::Base* noiseModel); // enabling serialization functionality void serialize() const; }; -typedef gtsam::BearingRangeFactor BearingRangeFactor2D; +typedef gtsam::BearingRangeFactor BearingRangeFactor2D; #include diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index a119096d4..09b128d91 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -133,6 +133,26 @@ template<> struct traits : public internal::Manifold { }; - /// Recover camera from 3*4 camera matrix - GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P); +template <> +struct Range { + typedef double result_type; + double operator()(const SimpleCamera& camera, const Point3& point, + OptionalJacobian<1, 11> 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 SimpleCamera& camera, const SimpleCamera& sc, + OptionalJacobian<1, 11> H1 = boost::none, + OptionalJacobian<1, 11> H2 = boost::none) { + return camera.range(sc, H1, H2); + } +}; + +/// Recover camera from 3*4 camera matrix +GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P); } diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index f78913448..1ad27865d 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -125,7 +125,7 @@ class RangeFactorWithTransform : public ExpressionFactor2 { private: /** Serialization function */ - friend typename boost::serialization::access; + friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp(