wrap Vector,Matrix for Values::at in the short test
parent
685b0cb62f
commit
347fed9377
|
@ -609,7 +609,7 @@ class Values {
|
||||||
void update(size_t j, Matrix t);
|
void update(size_t j, Matrix t);
|
||||||
|
|
||||||
template <T = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
template <T = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
||||||
gtsam::Rot3, gtsam::Pose3}>
|
gtsam::Rot3, gtsam::Pose3, Vector, Matrix}>
|
||||||
T at(size_t j);
|
T at(size_t j);
|
||||||
|
|
||||||
/// version for double
|
/// version for double
|
||||||
|
|
Loading…
Reference in New Issue