diff --git a/gtsam.h b/gtsam.h index d63563028..bf554986c 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1738,6 +1738,8 @@ class Values { void insert(size_t j, const gtsam::Cal3Bundler& 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, 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’ void update(size_t j, const gtsam::Point2& t); void update(size_t j, const gtsam::Point3& t); @@ -1750,9 +1752,11 @@ class Values { void update(size_t j, const gtsam::Cal3Bundler& t); void update(size_t j, const gtsam::EssentialMatrix& t); void update(size_t j, const gtsam::imuBias::ConstantBias& t); + void update(size_t j, Vector t); + void update(size_t j, Matrix t); template + gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::imuBias::ConstantBias ,Vector, Matrix}> // Parse Error T at(size_t j); }; @@ -2150,7 +2154,9 @@ class NonlinearISAM { #include #include -template +template // Parse Error virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const;