Merge pull request #1654 from borglab/fix/1648

release/4.3a0
Varun Agrawal 2023-10-12 16:49:18 -04:00 committed by GitHub
commit 244c9b654b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 17 additions and 8 deletions

View File

@ -59,10 +59,12 @@ class Values {
// enabling serialization functionality
void serialize() const;
// New in 4.0, we have to specialize every insert/update/at to generate
// wrappers Instead of the old: void insert(size_t j, const gtsam::Value&
// value); void update(size_t j, const gtsam::Value& val); gtsam::Value
// at(size_t j) const;
// New in 4.0, we have to specialize every insert/update/at
// to generate wrappers.
// Instead of the old:
// void insert(size_t j, const gtsam::Value& value);
// void update(size_t j, const gtsam::Value& val);
// gtsam::Value at(size_t j) const;
// The order is important: Vector has to precede Point2/Point3 so `atVector`
// can work for those fixed-size vectors.
@ -99,6 +101,10 @@ class Values {
template <T = {gtsam::Point2, gtsam::Point3}>
void insert(size_t j, const T& val);
// The order is important: Vector has to precede Point2/Point3 so `atVector`
// can work for those fixed-size vectors.
void update(size_t j, Vector vector);
void update(size_t j, Matrix matrix);
void update(size_t j, const gtsam::Point2& point2);
void update(size_t j, const gtsam::Point3& point3);
void update(size_t j, const gtsam::Rot2& rot2);
@ -125,10 +131,12 @@ class Values {
void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
void update(size_t j, const gtsam::NavState& nav_state);
void update(size_t j, Vector vector);
void update(size_t j, Matrix matrix);
void update(size_t j, double c);
// The order is important: Vector has to precede Point2/Point3 so `atVector`
// can work for those fixed-size vectors.
void insert_or_assign(size_t j, Vector vector);
void insert_or_assign(size_t j, Matrix matrix);
void insert_or_assign(size_t j, const gtsam::Point2& point2);
void insert_or_assign(size_t j, const gtsam::Point3& point3);
void insert_or_assign(size_t j, const gtsam::Rot2& rot2);
@ -165,8 +173,6 @@ class Values {
void insert_or_assign(size_t j,
const gtsam::imuBias::ConstantBias& constant_bias);
void insert_or_assign(size_t j, const gtsam::NavState& nav_state);
void insert_or_assign(size_t j, Vector vector);
void insert_or_assign(size_t j, Matrix matrix);
void insert_or_assign(size_t j, double c);
template <T = {gtsam::Point2,

View File

@ -156,6 +156,9 @@ virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor {
// enabling serialization functionality
void serialize() const;
gtsam::TriangulationResult point() const;
gtsam::TriangulationResult point(const gtsam::Values& values) const;
};
typedef gtsam::SmartProjectionPoseFactor<gtsam::Cal3_S2>