rearrange Values::insert to fix 1477

release/4.3a0
Varun Agrawal 2023-10-10 06:55:54 -04:00
parent b6dbb0fe92
commit d5d75274ec
1 changed files with 8 additions and 2 deletions

View File

@ -66,8 +66,6 @@ class Values {
// The order is important: Vector has to precede Point2/Point3 so `atVector`
// can work for those fixed-size vectors.
void insert(size_t j, Vector vector);
void insert(size_t j, Matrix matrix);
void insert(size_t j, const gtsam::Point2& point2);
void insert(size_t j, const gtsam::Point3& point3);
void insert(size_t j, const gtsam::Rot2& rot2);
@ -94,6 +92,10 @@ class Values {
void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
void insert(size_t j, const gtsam::NavState& nav_state);
// Vector and Matrix versions should go at the end
// to avoid collisions with Point2 and Point3
void insert(size_t j, Vector vector);
void insert(size_t j, Matrix matrix);
void insert(size_t j, double c);
template <T = {gtsam::Point2, gtsam::Point3}>
@ -125,6 +127,8 @@ 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);
// Vector and Matrix versions should go at the end
// to avoid collisions with Point2 and Point3
void update(size_t j, Vector vector);
void update(size_t j, Matrix matrix);
void update(size_t j, double c);
@ -165,6 +169,8 @@ 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);
// Vector and Matrix versions should go at the end
// to avoid collisions with Point2 and Point3
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);