binary measurement wrap
parent
ae5956bd10
commit
667fb9a4b9
44
gtsam.h
44
gtsam.h
|
@ -2568,10 +2568,12 @@ virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#include <gtsam/nonlinear/NonlinearEquality.h>
|
#include <gtsam/nonlinear/NonlinearEquality.h>
|
||||||
template<T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2, gtsam::imuBias::ConstantBias}>
|
template <T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
|
||||||
|
gtsam::SO3, gtsam::SO4, gtsam::SOn, gtsam::Rot3, gtsam::Pose2,
|
||||||
|
gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera,
|
||||||
|
gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2,
|
||||||
|
gtsam::imuBias::ConstantBias}>
|
||||||
virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
||||||
// Constructor - forces exact evaluation
|
// Constructor - forces exact evaluation
|
||||||
NonlinearEquality(size_t j, const T& feasible);
|
NonlinearEquality(size_t j, const T& feasible);
|
||||||
|
@ -2582,7 +2584,6 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#include <gtsam/sam/RangeFactor.h>
|
#include <gtsam/sam/RangeFactor.h>
|
||||||
template<POSE, POINT>
|
template<POSE, POINT>
|
||||||
virtual class RangeFactor : gtsam::NoiseModelFactor {
|
virtual class RangeFactor : gtsam::NoiseModelFactor {
|
||||||
|
@ -2880,6 +2881,41 @@ virtual class FrobeniusWormholeFactor : gtsam::NoiseModelFactor {
|
||||||
Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2);
|
Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/sfm/BinaryMeasurement.h>
|
||||||
|
template<T>
|
||||||
|
class BinaryMeasurement {
|
||||||
|
BinaryMeasurement(size_t key1, size_t key2, const T& measured,
|
||||||
|
const gtsam::noiseModel::Base* model);
|
||||||
|
size_t key1() const;
|
||||||
|
size_t key2() const;
|
||||||
|
T measured() const;
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef gtsam::BinaryMeasurement<gtsam::Unit3> BinaryMeasurementUnit3;
|
||||||
|
typedef gtsam::BinaryMeasurement<gtsam::Rot3> BinaryMeasurementRot3;
|
||||||
|
|
||||||
|
// std::vector<gtsam::BinaryMeasurement<Unit3>::shared_ptr>
|
||||||
|
class BinaryMeasurementUnit3s
|
||||||
|
{
|
||||||
|
BinaryMeasurementUnit3s();
|
||||||
|
size_t size() const;
|
||||||
|
gtsam::BinaryMeasurementUnit3* at(size_t i) const;
|
||||||
|
void push_back(const gtsam::BinaryMeasurementUnit3* measurement);
|
||||||
|
};
|
||||||
|
|
||||||
|
// std::vector<gtsam::BinaryMeasurement<Rot3>::shared_ptr>
|
||||||
|
class BinaryMeasurementRot3s
|
||||||
|
{
|
||||||
|
BinaryMeasurementRot3s();
|
||||||
|
size_t size() const;
|
||||||
|
gtsam::BinaryMeasurementRot3* at(size_t i) const;
|
||||||
|
void push_back(const gtsam::BinaryMeasurementRot3* measurement);
|
||||||
|
};
|
||||||
|
|
||||||
|
#include <gtsam/sfm/TranslationRecovery.h>
|
||||||
|
class TranslationRecovery {
|
||||||
|
TranslationRecovery()
|
||||||
|
}
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// Navigation
|
// Navigation
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
|
@ -91,4 +91,7 @@ public:
|
||||||
return measured_;
|
return measured_;
|
||||||
}
|
}
|
||||||
}; // \class BetweenMeasurement
|
}; // \class BetweenMeasurement
|
||||||
|
|
||||||
|
using BinaryMeasurementUnit3s = std::vector<gtsam::BinaryMeasurement<Unit3>::shared_ptr>;
|
||||||
|
using BinaryMeasurementRot3s = std::vector<gtsam::BinaryMeasurement<Rot3>::shared_ptr>;
|
||||||
}
|
}
|
Loading…
Reference in New Issue