Merge remote-tracking branch 'origin/feature/sam_sfm_directories' into feature/sam_sfm_directories

release/4.3a0
Frank Dellaert 2015-07-13 23:44:57 -07:00
commit 5f6f9847d6
3 changed files with 29 additions and 9 deletions

12
gtsam.h
View File

@ -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<gtsam::Pose2, gtsam::Point2, gtsam::Rot2> BearingFactor2D;
#include <gtsam/sam/BearingRangeFactor.h>
template<POSE, POINT, BEARING>
template<POSE, POINT, BEARING, RANGE>
virtual class BearingRangeFactor : gtsam::NoiseModelFactor {
BearingRangeFactor(size_t poseKey, size_t pointKey, const BEARING& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel);
pair<MEASURED, double> 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<gtsam::Pose2, gtsam::Point2, gtsam::Rot2> BearingRangeFactor2D;
typedef gtsam::BearingRangeFactor<gtsam::Pose2, gtsam::Point2, gtsam::Rot2, double> BearingRangeFactor2D;
#include <gtsam/slam/ProjectionFactor.h>

View File

@ -133,6 +133,26 @@ template<>
struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {
};
/// Recover camera from 3*4 camera matrix
GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P);
template <>
struct Range<SimpleCamera, Point3> {
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<SimpleCamera, SimpleCamera> {
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);
}

View File

@ -125,7 +125,7 @@ class RangeFactorWithTransform : public ExpressionFactor2<T, A1, A2> {
private:
/** Serialization function */
friend typename boost::serialization::access;
friend class boost::serialization::access;
template <typename ARCHIVE>
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
ar& boost::serialization::make_nvp(