Skip to content

Commit e18ecc3

Browse files
authored
Merge pull request #959 from borglab/values/upsert
Add new insert_or_assign method to Values
2 parents 36dafed + 96652ca commit e18ecc3

File tree

5 files changed

+81
-0
lines changed

5 files changed

+81
-0
lines changed

gtsam/nonlinear/Values-inl.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -391,4 +391,10 @@ namespace gtsam {
391391
update(j, static_cast<const Value&>(GenericValue<ValueType>(val)));
392392
}
393393

394+
// insert_or_assign with templated value
395+
template <typename ValueType>
396+
void Values::insert_or_assign(Key j, const ValueType& val) {
397+
insert_or_assign(j, static_cast<const Value&>(GenericValue<ValueType>(val)));
398+
}
399+
394400
}

gtsam/nonlinear/Values.cpp

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -171,6 +171,25 @@ namespace gtsam {
171171
}
172172
}
173173

174+
/* ************************************************************************ */
175+
void Values::insert_or_assign(Key j, const Value& val) {
176+
if (this->exists(j)) {
177+
// If key already exists, perform an update.
178+
this->update(j, val);
179+
} else {
180+
// If key does not exist, perform an insert.
181+
this->insert(j, val);
182+
}
183+
}
184+
185+
/* ************************************************************************ */
186+
void Values::insert_or_assign(const Values& values) {
187+
for (const_iterator key_value = values.begin(); key_value != values.end();
188+
++key_value) {
189+
this->insert_or_assign(key_value->key, key_value->value);
190+
}
191+
}
192+
174193
/* ************************************************************************* */
175194
void Values::erase(Key j) {
176195
KeyValueMap::iterator item = values_.find(j);

gtsam/nonlinear/Values.h

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -285,6 +285,19 @@ namespace gtsam {
285285
/** update the current available values without adding new ones */
286286
void update(const Values& values);
287287

288+
/// If key j exists, update value, else perform an insert.
289+
void insert_or_assign(Key j, const Value& val);
290+
291+
/**
292+
* Update a set of variables.
293+
* If any variable key doe not exist, then perform an insert.
294+
*/
295+
void insert_or_assign(const Values& values);
296+
297+
/// Templated version to insert_or_assign a variable with the given j.
298+
template <typename ValueType>
299+
void insert_or_assign(Key j, const ValueType& val);
300+
288301
/** Remove a variable from the config, throws KeyDoesNotExist<J> if j is not present */
289302
void erase(Key j);
290303

gtsam/nonlinear/nonlinear.i

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -275,6 +275,7 @@ class Values {
275275

276276
void insert(const gtsam::Values& values);
277277
void update(const gtsam::Values& values);
278+
void insert_or_assign(const gtsam::Values& values);
278279
void erase(size_t j);
279280
void swap(gtsam::Values& values);
280281

@@ -351,6 +352,32 @@ class Values {
351352
void update(size_t j, Matrix matrix);
352353
void update(size_t j, double c);
353354

355+
void insert_or_assign(size_t j, const gtsam::Point2& point2);
356+
void insert_or_assign(size_t j, const gtsam::Point3& point3);
357+
void insert_or_assign(size_t j, const gtsam::Rot2& rot2);
358+
void insert_or_assign(size_t j, const gtsam::Pose2& pose2);
359+
void insert_or_assign(size_t j, const gtsam::SO3& R);
360+
void insert_or_assign(size_t j, const gtsam::SO4& Q);
361+
void insert_or_assign(size_t j, const gtsam::SOn& P);
362+
void insert_or_assign(size_t j, const gtsam::Rot3& rot3);
363+
void insert_or_assign(size_t j, const gtsam::Pose3& pose3);
364+
void insert_or_assign(size_t j, const gtsam::Unit3& unit3);
365+
void insert_or_assign(size_t j, const gtsam::Cal3_S2& cal3_s2);
366+
void insert_or_assign(size_t j, const gtsam::Cal3DS2& cal3ds2);
367+
void insert_or_assign(size_t j, const gtsam::Cal3Bundler& cal3bundler);
368+
void insert_or_assign(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
369+
void insert_or_assign(size_t j, const gtsam::Cal3Unified& cal3unified);
370+
void insert_or_assign(size_t j, const gtsam::EssentialMatrix& essential_matrix);
371+
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3_S2>& camera);
372+
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
373+
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
374+
void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
375+
void insert_or_assign(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
376+
void insert_or_assign(size_t j, const gtsam::NavState& nav_state);
377+
void insert_or_assign(size_t j, Vector vector);
378+
void insert_or_assign(size_t j, Matrix matrix);
379+
void insert_or_assign(size_t j, double c);
380+
354381
template <T = {gtsam::Point2,
355382
gtsam::Point3,
356383
gtsam::Rot2,

gtsam/nonlinear/tests/testValues.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,22 @@ TEST( Values, update_element )
172172
CHECK(assert_equal((Vector)v2, cfg.at<Vector3>(key1)));
173173
}
174174

175+
TEST(Values, InsertOrAssign) {
176+
Values values;
177+
Key X(0);
178+
double x = 1;
179+
180+
CHECK(values.size() == 0);
181+
// This should perform an insert.
182+
values.insert_or_assign(X, x);
183+
EXPECT(assert_equal(values.at<double>(X), x));
184+
185+
// This should perform an update.
186+
double y = 2;
187+
values.insert_or_assign(X, y);
188+
EXPECT(assert_equal(values.at<double>(X), y));
189+
}
190+
175191
/* ************************************************************************* */
176192
TEST(Values, basic_functions)
177193
{

0 commit comments

Comments
 (0)