Skip to content

Commit f6dbcb6

Browse files
committed
update gtsam:: namespace in values.i
1 parent 2db6178 commit f6dbcb6

File tree

1 file changed

+11
-11
lines changed

1 file changed

+11
-11
lines changed

gtsam/nonlinear/values.i

+11-11
Original file line numberDiff line numberDiff line change
@@ -66,10 +66,10 @@ class Values {
6666
// void update(size_t j, const gtsam::Value& val);
6767
// gtsam::Value at(size_t j) const;
6868

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`
7070
// 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);
7373
void insert(size_t j, const gtsam::Point2& point2);
7474
void insert(size_t j, const gtsam::Point3& point3);
7575
void insert(size_t j, const gtsam::Rot2& rot2);
@@ -101,10 +101,10 @@ class Values {
101101
template <T = {gtsam::Point2, gtsam::Point3}>
102102
void insert(size_t j, const T& val);
103103

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`
105105
// 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);
108108
void update(size_t j, const gtsam::Point2& point2);
109109
void update(size_t j, const gtsam::Point3& point3);
110110
void update(size_t j, const gtsam::Rot2& rot2);
@@ -133,10 +133,10 @@ class Values {
133133
void update(size_t j, const gtsam::NavState& nav_state);
134134
void update(size_t j, double c);
135135

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`
137137
// 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);
140140
void insert_or_assign(size_t j, const gtsam::Point2& point2);
141141
void insert_or_assign(size_t j, const gtsam::Point3& point3);
142142
void insert_or_assign(size_t j, const gtsam::Rot2& rot2);
@@ -201,8 +201,8 @@ class Values {
201201
gtsam::PinholePose<gtsam::Cal3Unified>,
202202
gtsam::imuBias::ConstantBias,
203203
gtsam::NavState,
204-
Vector,
205-
Matrix,
204+
gtsam::Vector,
205+
gtsam::Matrix,
206206
double}>
207207
T at(size_t j);
208208
};

0 commit comments

Comments
 (0)