@@ -161,31 +161,31 @@ class FactorIndices {
161
161
namespace utilities {
162
162
163
163
#include < gtsam/nonlinear/utilities.h>
164
- gtsam::KeyList createKeyList (Vector I);
165
- gtsam::KeyList createKeyList (string s, Vector I);
166
- gtsam::KeyVector createKeyVector (Vector I);
167
- gtsam::KeyVector createKeyVector (string s, Vector I);
168
- gtsam::KeySet createKeySet (Vector I);
169
- gtsam::KeySet createKeySet (string s, Vector I);
170
- Matrix extractPoint2 (const gtsam::Values& values);
171
- Matrix extractPoint3 (const gtsam::Values& values);
164
+ gtsam::KeyList createKeyList (gtsam:: Vector I);
165
+ gtsam::KeyList createKeyList (string s, gtsam:: Vector I);
166
+ gtsam::KeyVector createKeyVector (gtsam:: Vector I);
167
+ gtsam::KeyVector createKeyVector (string s, gtsam:: Vector I);
168
+ gtsam::KeySet createKeySet (gtsam:: Vector I);
169
+ gtsam::KeySet createKeySet (string s, gtsam:: Vector I);
170
+ gtsam:: Matrix extractPoint2 (const gtsam::Values& values);
171
+ gtsam:: Matrix extractPoint3 (const gtsam::Values& values);
172
172
gtsam::Values allPose2s (gtsam::Values& values);
173
- Matrix extractPose2 (const gtsam::Values& values);
173
+ gtsam:: Matrix extractPose2 (const gtsam::Values& values);
174
174
gtsam::Values allPose3s (gtsam::Values& values);
175
- Matrix extractPose3 (const gtsam::Values& values);
176
- Matrix extractVectors (const gtsam::Values& values, char c);
175
+ gtsam:: Matrix extractPose3 (const gtsam::Values& values);
176
+ gtsam:: Matrix extractVectors (const gtsam::Values& values, char c);
177
177
void perturbPoint2 (gtsam::Values& values, double sigma, int seed = 42u );
178
178
void perturbPose2 (gtsam::Values& values, double sigmaT, double sigmaR,
179
179
int seed = 42u );
180
180
void perturbPoint3 (gtsam::Values& values, double sigma, int seed = 42u );
181
181
void insertBackprojections (gtsam::Values& values,
182
182
const gtsam::PinholeCamera<gtsam::Cal3_S2>& c,
183
- Vector J, Matrix Z, double depth);
183
+ gtsam:: Vector J, gtsam:: Matrix Z, double depth);
184
184
void insertProjectionFactors (
185
- gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z,
185
+ gtsam::NonlinearFactorGraph& graph, size_t i, gtsam:: Vector J, gtsam:: Matrix Z,
186
186
const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K,
187
187
const gtsam::Pose3& body_P_sensor = gtsam::Pose3());
188
- Matrix reprojectionErrors (const gtsam::NonlinearFactorGraph& graph,
188
+ gtsam:: Matrix reprojectionErrors (const gtsam::NonlinearFactorGraph& graph,
189
189
const gtsam::Values& values);
190
190
gtsam::Values localToWorld (const gtsam::Values& local,
191
191
const gtsam::Pose2& base);
0 commit comments