GTSAM header that gets parsed correctly
parent
b12255285b
commit
c9ca9c82a0
11
gtsam.h
11
gtsam.h
|
@ -1739,7 +1739,7 @@ class Values {
|
||||||
void insert(size_t j, const gtsam::EssentialMatrix& t);
|
void insert(size_t j, const gtsam::EssentialMatrix& t);
|
||||||
void insert(size_t j, const gtsam::imuBias::ConstantBias& t);
|
void insert(size_t j, const gtsam::imuBias::ConstantBias& t);
|
||||||
void insert(size_t j, Vector t);
|
void insert(size_t j, Vector t);
|
||||||
void insert(size_t j, Matrix t); //git/gtsam/gtsam/base/Manifold.h:254:1: error: invalid application of ‘sizeof’ to incomplete type ‘boost::STATIC_ASSERTION_FAILURE<false>’
|
void insert(size_t j, Matrix t);
|
||||||
|
|
||||||
void update(size_t j, const gtsam::Point2& t);
|
void update(size_t j, const gtsam::Point2& t);
|
||||||
void update(size_t j, const gtsam::Point3& t);
|
void update(size_t j, const gtsam::Point3& t);
|
||||||
|
@ -1755,8 +1755,7 @@ class Values {
|
||||||
void update(size_t j, Vector t);
|
void update(size_t j, Vector t);
|
||||||
void update(size_t j, Matrix t);
|
void update(size_t j, Matrix t);
|
||||||
|
|
||||||
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2,
|
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2, gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::EssentialMatrix, gtsam::imuBias::ConstantBias, Vector, Matrix}>
|
||||||
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::imuBias::ConstantBias ,Vector, Matrix}> // Parse Error
|
|
||||||
T at(size_t j);
|
T at(size_t j);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -2154,9 +2153,7 @@ class NonlinearISAM {
|
||||||
#include <gtsam/geometry/StereoPoint2.h>
|
#include <gtsam/geometry/StereoPoint2.h>
|
||||||
|
|
||||||
#include <gtsam/slam/PriorFactor.h>
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
template<T = { gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
|
template<T = { gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias}>
|
||||||
gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,
|
|
||||||
gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias, Vector, Matrix }> // Parse Error
|
|
||||||
virtual class PriorFactor : gtsam::NoiseModelFactor {
|
virtual class PriorFactor : gtsam::NoiseModelFactor {
|
||||||
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
|
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
|
||||||
T prior() const;
|
T prior() const;
|
||||||
|
@ -2167,7 +2164,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor {
|
||||||
|
|
||||||
|
|
||||||
#include <gtsam/slam/BetweenFactor.h>
|
#include <gtsam/slam/BetweenFactor.h>
|
||||||
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::imuBias::ConstantBias, Vector, Matrix}> // Parse Error
|
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::imuBias::ConstantBias}>
|
||||||
virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
virtual class BetweenFactor : gtsam::NoiseModelFactor {
|
||||||
BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
|
BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
|
||||||
T measured() const;
|
T measured() const;
|
||||||
|
|
Loading…
Reference in New Issue