Merge remote-tracking branch 'origin/feature/sam_sfm_directories' into feature/sam_sfm_directories
commit
5f6f9847d6
12
gtsam.h
12
gtsam.h
|
|
@ -1,4 +1,5 @@
|
||||||
/**
|
/**
|
||||||
|
|
||||||
* GTSAM Wrap Module Definition
|
* GTSAM Wrap Module Definition
|
||||||
*
|
*
|
||||||
* These are the current classes available through the matlab toolbox interface,
|
* 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;
|
typedef gtsam::BearingFactor<gtsam::Pose2, gtsam::Point2, gtsam::Rot2> BearingFactor2D;
|
||||||
|
|
||||||
|
|
||||||
#include <gtsam/sam/BearingRangeFactor.h>
|
#include <gtsam/sam/BearingRangeFactor.h>
|
||||||
template<POSE, POINT, BEARING>
|
template<POSE, POINT, BEARING, RANGE>
|
||||||
virtual class BearingRangeFactor : gtsam::NoiseModelFactor {
|
virtual class BearingRangeFactor : gtsam::NoiseModelFactor {
|
||||||
BearingRangeFactor(size_t poseKey, size_t pointKey, const BEARING& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel);
|
BearingRangeFactor(size_t poseKey, size_t pointKey,
|
||||||
|
const BEARING& measuredBearing, const RANGE& measuredRange,
|
||||||
pair<MEASURED, double> measured() const;
|
const gtsam::noiseModel::Base* noiseModel);
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serialize() const;
|
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>
|
#include <gtsam/slam/ProjectionFactor.h>
|
||||||
|
|
|
||||||
|
|
@ -133,6 +133,26 @@ template<>
|
||||||
struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {
|
struct traits<const SimpleCamera> : public internal::Manifold<SimpleCamera> {
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Recover camera from 3*4 camera matrix
|
template <>
|
||||||
GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P);
|
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);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -125,7 +125,7 @@ class RangeFactorWithTransform : public ExpressionFactor2<T, A1, A2> {
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/** Serialization function */
|
/** Serialization function */
|
||||||
friend typename boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template <typename ARCHIVE>
|
template <typename ARCHIVE>
|
||||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||||
ar& boost::serialization::make_nvp(
|
ar& boost::serialization::make_nvp(
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue