Fixed version of at
parent
c22a2d80d2
commit
4542292af9
8
gtsam.h
8
gtsam.h
|
|
@ -1733,9 +1733,6 @@ class Values {
|
||||||
void insert(size_t j, Vector t);
|
void insert(size_t j, Vector t);
|
||||||
void insert(size_t j, Matrix t);
|
void insert(size_t j, Matrix t);
|
||||||
|
|
||||||
// Fixed size version
|
|
||||||
void insertFixed(size_t j, Vector t, size_t n);
|
|
||||||
|
|
||||||
void update(size_t j, const gtsam::Point2& t);
|
void update(size_t j, const gtsam::Point2& t);
|
||||||
void update(size_t j, const gtsam::Point3& t);
|
void update(size_t j, const gtsam::Point3& t);
|
||||||
void update(size_t j, const gtsam::Rot2& t);
|
void update(size_t j, const gtsam::Rot2& t);
|
||||||
|
|
@ -1752,6 +1749,11 @@ class Values {
|
||||||
|
|
||||||
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2, gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::EssentialMatrix, gtsam::imuBias::ConstantBias, Vector, Matrix}>
|
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2, gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::EssentialMatrix, gtsam::imuBias::ConstantBias, Vector, Matrix}>
|
||||||
T at(size_t j);
|
T at(size_t j);
|
||||||
|
|
||||||
|
// Fixed size versions, for n in 1..9
|
||||||
|
void insertFixed(size_t j, Vector t, size_t n);
|
||||||
|
Vector atFixed(size_t j, size_t n);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
// Actually a FastList<Key>
|
// Actually a FastList<Key>
|
||||||
|
|
|
||||||
|
|
@ -112,6 +112,24 @@ namespace gtsam {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
Vector Values::atFixed(Key j, size_t n) {
|
||||||
|
switch (n) {
|
||||||
|
case 1: return at<Vector1>(j);
|
||||||
|
case 2: return at<Vector2>(j);
|
||||||
|
case 3: return at<Vector3>(j);
|
||||||
|
case 4: return at<Vector4>(j);
|
||||||
|
case 5: return at<Vector5>(j);
|
||||||
|
case 6: return at<Vector6>(j);
|
||||||
|
case 7: return at<Vector7>(j);
|
||||||
|
case 8: return at<Vector8>(j);
|
||||||
|
case 9: return at<Vector9>(j);
|
||||||
|
default:
|
||||||
|
throw runtime_error(
|
||||||
|
"Values::at fixed size can only handle n in 1..9");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
const Value& Values::at(Key j) const {
|
const Value& Values::at(Key j) const {
|
||||||
// Find the item
|
// Find the item
|
||||||
|
|
|
||||||
|
|
@ -180,6 +180,10 @@ namespace gtsam {
|
||||||
template<typename ValueType>
|
template<typename ValueType>
|
||||||
const ValueType& at(Key j) const;
|
const ValueType& at(Key j) const;
|
||||||
|
|
||||||
|
/// Special version for small fixed size vectors, for matlab/python
|
||||||
|
/// throws truntime error if n<1 || n>9
|
||||||
|
Vector atFixed(Key j, size_t n);
|
||||||
|
|
||||||
/** Retrieve a variable by key \c j. This version returns a reference
|
/** Retrieve a variable by key \c j. This version returns a reference
|
||||||
* to the base Value class, and needs to be casted before use.
|
* to the base Value class, and needs to be casted before use.
|
||||||
* @param j Retrieve the value associated with this key
|
* @param j Retrieve the value associated with this key
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue