Address comments by Frank

release/4.3a0
Fan Jiang 2022-04-14 13:05:15 -04:00
parent ed34ee3245
commit 1b63fb51eb
2 changed files with 12 additions and 7 deletions

View File

@ -279,10 +279,11 @@ namespace gtsam {
template <typename ValueType> template <typename ValueType>
struct handle { struct handle {
ValueType operator()(Key j, const Value* const pointer) { ValueType operator()(Key j, const Value* const pointer) {
try { auto ptr = dynamic_cast<const GenericValue<ValueType>*>(pointer);
if (ptr) {
// value returns a const ValueType&, and the return makes a copy !!!!! // value returns a const ValueType&, and the return makes a copy !!!!!
return dynamic_cast<const GenericValue<ValueType>&>(*pointer).value(); return ptr->value();
} catch (std::bad_cast&) { } else {
throw ValuesIncorrectType(j, typeid(*pointer), typeid(ValueType)); throw ValuesIncorrectType(j, typeid(*pointer), typeid(ValueType));
} }
} }
@ -367,10 +368,10 @@ namespace gtsam {
if(item != values_.end()) { if(item != values_.end()) {
// dynamic cast the type and throw exception if incorrect // dynamic cast the type and throw exception if incorrect
const Value& value = *item->second; auto ptr = dynamic_cast<const GenericValue<ValueType>*>(item->second);
try { if (ptr) {
return dynamic_cast<const GenericValue<ValueType>&>(value).value(); return ptr->value();
} catch (std::bad_cast &) { } else {
// NOTE(abe): clang warns about potential side effects if done in typeid // NOTE(abe): clang warns about potential side effects if done in typeid
const Value* value = item->second; const Value* value = item->second;
throw ValuesIncorrectType(j, typeid(*value), typeid(ValueType)); throw ValuesIncorrectType(j, typeid(*value), typeid(ValueType));

View File

@ -245,6 +245,10 @@ class Values {
void insert(size_t j, const gtsam::ParameterMatrix<14>& X); void insert(size_t j, const gtsam::ParameterMatrix<14>& X);
void insert(size_t j, const gtsam::ParameterMatrix<15>& X); void insert(size_t j, const gtsam::ParameterMatrix<15>& X);
template <T = {gtsam::Point2,
gtsam::Point3}>
void insert(size_t j, const T& val);
void update(size_t j, const gtsam::Point2& point2); 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::Point3& point3);
void update(size_t j, const gtsam::Rot2& rot2); void update(size_t j, const gtsam::Rot2& rot2);