update gtsam:: namespace in slam.i
parent
49ff90dda9
commit
2ea9d1bcf3
|
@ -12,7 +12,7 @@ namespace gtsam {
|
|||
// ######
|
||||
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
template <T = {double, Vector, gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::SO3,
|
||||
template <T = {double, gtsam::Vector, gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::SO3,
|
||||
gtsam::SO4, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Similarity3,
|
||||
gtsam::imuBias::ConstantBias}>
|
||||
virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
||||
|
@ -227,7 +227,7 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
|
|||
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||
gtsam::DefaultKeyFormatter) const;
|
||||
bool equals(const gtsam::EssentialMatrixFactor& other, double tol) const;
|
||||
Vector evaluateError(const gtsam::EssentialMatrix& E) const;
|
||||
gtsam::Vector evaluateError(const gtsam::EssentialMatrix& E) const;
|
||||
};
|
||||
|
||||
#include <gtsam/slam/EssentialMatrixConstraint.h>
|
||||
|
@ -237,7 +237,7 @@ virtual class EssentialMatrixConstraint : gtsam::NoiseModelFactor {
|
|||
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||
gtsam::DefaultKeyFormatter) const;
|
||||
bool equals(const gtsam::EssentialMatrixConstraint& other, double tol) const;
|
||||
Vector evaluateError(const gtsam::Pose3& p1, const gtsam::Pose3& p2) const;
|
||||
gtsam::Vector evaluateError(const gtsam::Pose3& p1, const gtsam::Pose3& p2) const;
|
||||
const gtsam::EssentialMatrix& measured() const;
|
||||
};
|
||||
|
||||
|
@ -336,7 +336,7 @@ virtual class FrobeniusFactor : gtsam::NoiseModelFactor {
|
|||
FrobeniusFactor(size_t key1, size_t key2);
|
||||
FrobeniusFactor(size_t key1, size_t key2, gtsam::noiseModel::Base* model);
|
||||
|
||||
Vector evaluateError(const T& R1, const T& R2);
|
||||
gtsam::Vector evaluateError(const T& R1, const T& R2);
|
||||
};
|
||||
|
||||
template <T = {gtsam::SO3, gtsam::SO4}>
|
||||
|
@ -345,7 +345,7 @@ virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor {
|
|||
FrobeniusBetweenFactor(size_t key1, size_t key2, const T& R12,
|
||||
gtsam::noiseModel::Base* model);
|
||||
|
||||
Vector evaluateError(const T& R1, const T& R2);
|
||||
gtsam::Vector evaluateError(const T& R1, const T& R2);
|
||||
};
|
||||
|
||||
#include <gtsam/slam/lago.h>
|
||||
|
|
Loading…
Reference in New Issue