diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index d0f8a47905..6829e859b6 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -338,19 +338,18 @@ namespace gtsam { } // internal /* ************************************************************************* */ - template - ValueType Values::at(Key j) const { + template + const ValueType Values::at(Key j) const { // Find the item KeyValueMap::const_iterator item = values_.find(j); // Throw exception if it does not exist - if(item == values_.end()) - throw ValuesKeyDoesNotExist("at", j); + if (item == values_.end()) throw ValuesKeyDoesNotExist("at", j); - // Check the type and throw exception if incorrect - // h() split in two lines to avoid internal compiler error (MSVC2017) - auto h = internal::handle(); - return h(j,item->second); + // Check the type and throw exception if incorrect + // h() split in two lines to avoid internal compiler error (MSVC2017) + auto h = internal::handle(); + return h(j, item->second); } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index b49188b68d..120c8839c5 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -187,8 +187,8 @@ namespace gtsam { * Dynamic matrices/vectors can be retrieved as fixed-size, but not vice-versa. * @return The stored value */ - template - ValueType at(Key j) const; + template + const ValueType at(Key j) const; /// version for double double atDouble(size_t key) const { return at(key);}