Skip to content

Commit

Permalink
replace upsert with insert_or_assign
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal committed Dec 15, 2021
1 parent 8c3ce25 commit 96652ca
Show file tree
Hide file tree
Showing 5 changed files with 48 additions and 44 deletions.
6 changes: 3 additions & 3 deletions gtsam/nonlinear/Values-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -391,10 +391,10 @@ namespace gtsam {
update(j, static_cast<const Value&>(GenericValue<ValueType>(val)));
}

// upsert with templated value
// insert_or_assign with templated value
template <typename ValueType>
void Values::upsert(Key j, const ValueType& val) {
upsert(j, static_cast<const Value&>(GenericValue<ValueType>(val)));
void Values::insert_or_assign(Key j, const ValueType& val) {
insert_or_assign(j, static_cast<const Value&>(GenericValue<ValueType>(val)));
}

}
13 changes: 7 additions & 6 deletions gtsam/nonlinear/Values.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,8 +171,8 @@ namespace gtsam {
}
}

/* ************************************************************************* */
void Values::upsert(Key j, const Value& val) {
/* ************************************************************************ */
void Values::insert_or_assign(Key j, const Value& val) {
if (this->exists(j)) {
// If key already exists, perform an update.
this->update(j, val);
Expand All @@ -182,10 +182,11 @@ namespace gtsam {
}
}

/* ************************************************************************* */
void Values::upsert(const Values& values) {
for(const_iterator key_value = values.begin(); key_value != values.end(); ++key_value) {
this->upsert(key_value->key, key_value->value);
/* ************************************************************************ */
void Values::insert_or_assign(const Values& values) {
for (const_iterator key_value = values.begin(); key_value != values.end();
++key_value) {
this->insert_or_assign(key_value->key, key_value->value);
}
}

Expand Down
15 changes: 9 additions & 6 deletions gtsam/nonlinear/Values.h
Original file line number Diff line number Diff line change
Expand Up @@ -285,15 +285,18 @@ namespace gtsam {
/** update the current available values without adding new ones */
void update(const Values& values);

/** Update a variable with key j. If j does not exist, then perform an insert. */
void upsert(Key j, const Value& val);
/// If key j exists, update value, else perform an insert.
void insert_or_assign(Key j, const Value& val);

/** Update a set of variables. If any variable key doe not exist, then perform an insert. */
void upsert(const Values& values);
/**
* Update a set of variables.
* If any variable key doe not exist, then perform an insert.
*/
void insert_or_assign(const Values& values);

/** Templated version to upsert (update/insert) a variable with the given j. */
/// Templated version to insert_or_assign a variable with the given j.
template <typename ValueType>
void upsert(Key j, const ValueType& val);
void insert_or_assign(Key j, const ValueType& val);

/** Remove a variable from the config, throws KeyDoesNotExist<J> if j is not present */
void erase(Key j);
Expand Down
52 changes: 26 additions & 26 deletions gtsam/nonlinear/nonlinear.i
Original file line number Diff line number Diff line change
Expand Up @@ -275,7 +275,7 @@ class Values {

void insert(const gtsam::Values& values);
void update(const gtsam::Values& values);
void upsert(const gtsam::Values& values);
void insert_or_assign(const gtsam::Values& values);
void erase(size_t j);
void swap(gtsam::Values& values);

Expand Down Expand Up @@ -352,31 +352,31 @@ class Values {
void update(size_t j, Matrix matrix);
void update(size_t j, double c);

void upsert(size_t j, const gtsam::Point2& point2);
void upsert(size_t j, const gtsam::Point3& point3);
void upsert(size_t j, const gtsam::Rot2& rot2);
void upsert(size_t j, const gtsam::Pose2& pose2);
void upsert(size_t j, const gtsam::SO3& R);
void upsert(size_t j, const gtsam::SO4& Q);
void upsert(size_t j, const gtsam::SOn& P);
void upsert(size_t j, const gtsam::Rot3& rot3);
void upsert(size_t j, const gtsam::Pose3& pose3);
void upsert(size_t j, const gtsam::Unit3& unit3);
void upsert(size_t j, const gtsam::Cal3_S2& cal3_s2);
void upsert(size_t j, const gtsam::Cal3DS2& cal3ds2);
void upsert(size_t j, const gtsam::Cal3Bundler& cal3bundler);
void upsert(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
void upsert(size_t j, const gtsam::Cal3Unified& cal3unified);
void upsert(size_t j, const gtsam::EssentialMatrix& essential_matrix);
void upsert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3_S2>& camera);
void upsert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
void upsert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
void upsert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
void upsert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
void upsert(size_t j, const gtsam::NavState& nav_state);
void upsert(size_t j, Vector vector);
void upsert(size_t j, Matrix matrix);
void upsert(size_t j, double c);
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);
void insert_or_assign(size_t j, const gtsam::Pose2& pose2);
void insert_or_assign(size_t j, const gtsam::SO3& R);
void insert_or_assign(size_t j, const gtsam::SO4& Q);
void insert_or_assign(size_t j, const gtsam::SOn& P);
void insert_or_assign(size_t j, const gtsam::Rot3& rot3);
void insert_or_assign(size_t j, const gtsam::Pose3& pose3);
void insert_or_assign(size_t j, const gtsam::Unit3& unit3);
void insert_or_assign(size_t j, const gtsam::Cal3_S2& cal3_s2);
void insert_or_assign(size_t j, const gtsam::Cal3DS2& cal3ds2);
void insert_or_assign(size_t j, const gtsam::Cal3Bundler& cal3bundler);
void insert_or_assign(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
void insert_or_assign(size_t j, const gtsam::Cal3Unified& cal3unified);
void insert_or_assign(size_t j, const gtsam::EssentialMatrix& essential_matrix);
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3_S2>& camera);
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
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,
gtsam::Point3,
Expand Down
6 changes: 3 additions & 3 deletions gtsam/nonlinear/tests/testValues.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,19 +172,19 @@ TEST( Values, update_element )
CHECK(assert_equal((Vector)v2, cfg.at<Vector3>(key1)));
}

TEST(Values, upsert) {
TEST(Values, InsertOrAssign) {
Values values;
Key X(0);
double x = 1;

CHECK(values.size() == 0);
// This should perform an insert.
values.upsert(X, x);
values.insert_or_assign(X, x);
EXPECT(assert_equal(values.at<double>(X), x));

// This should perform an update.
double y = 2;
values.upsert(X, y);
values.insert_or_assign(X, y);
EXPECT(assert_equal(values.at<double>(X), y));
}

Expand Down

0 comments on commit 96652ca

Please sign in to comment.