@@ -66,10 +66,10 @@ class Values {
66
66
// void update(size_t j, const gtsam::Value& val);
67
67
// gtsam::Value at(size_t j) const;
68
68
69
- // The order is important: Vector has to precede Point2/Point3 so `atVector`
69
+ // The order is important: gtsam:: Vector has to precede Point2/Point3 so `atVector`
70
70
// can work for those fixed-size vectors.
71
- void insert (size_t j, Vector vector);
72
- void insert (size_t j, Matrix matrix);
71
+ void insert (size_t j, gtsam:: Vector vector);
72
+ void insert (size_t j, gtsam:: Matrix matrix);
73
73
void insert (size_t j, const gtsam::Point2& point2);
74
74
void insert (size_t j, const gtsam::Point3& point3);
75
75
void insert (size_t j, const gtsam::Rot2& rot2);
@@ -101,10 +101,10 @@ class Values {
101
101
template <T = {gtsam::Point2, gtsam::Point3}>
102
102
void insert (size_t j, const T& val);
103
103
104
- // The order is important: Vector has to precede Point2/Point3 so `atVector`
104
+ // The order is important: gtsam:: Vector has to precede Point2/Point3 so `atVector`
105
105
// can work for those fixed-size vectors.
106
- void update (size_t j, Vector vector);
107
- void update (size_t j, Matrix matrix);
106
+ void update (size_t j, gtsam:: Vector vector);
107
+ void update (size_t j, gtsam:: Matrix matrix);
108
108
void update (size_t j, const gtsam::Point2& point2);
109
109
void update (size_t j, const gtsam::Point3& point3);
110
110
void update (size_t j, const gtsam::Rot2& rot2);
@@ -133,10 +133,10 @@ class Values {
133
133
void update (size_t j, const gtsam::NavState& nav_state);
134
134
void update (size_t j, double c);
135
135
136
- // The order is important: Vector has to precede Point2/Point3 so `atVector`
136
+ // The order is important: gtsam:: Vector has to precede Point2/Point3 so `atVector`
137
137
// can work for those fixed-size vectors.
138
- void insert_or_assign (size_t j, Vector vector);
139
- void insert_or_assign (size_t j, Matrix matrix);
138
+ void insert_or_assign (size_t j, gtsam:: Vector vector);
139
+ void insert_or_assign (size_t j, gtsam:: Matrix matrix);
140
140
void insert_or_assign (size_t j, const gtsam::Point2& point2);
141
141
void insert_or_assign (size_t j, const gtsam::Point3& point3);
142
142
void insert_or_assign (size_t j, const gtsam::Rot2& rot2);
@@ -201,8 +201,8 @@ class Values {
201
201
gtsam::PinholePose<gtsam::Cal3Unified>,
202
202
gtsam::imuBias::ConstantBias,
203
203
gtsam::NavState,
204
- Vector,
205
- Matrix,
204
+ gtsam:: Vector,
205
+ gtsam:: Matrix,
206
206
double }>
207
207
T at (size_t j);
208
208
};
0 commit comments