gtsam  4.0.0
gtsam
gtsam_unstable.h
1 
5 // specify the classes from gtsam we are using
6 virtual class gtsam::Value;
7 class gtsam::Vector6;
8 class gtsam::LieScalar;
9 class gtsam::LieVector;
10 class gtsam::Point2;
11 class gtsam::Point2Vector;
12 class gtsam::Rot2;
13 class gtsam::Pose2;
14 class gtsam::Point3;
15 class gtsam::Rot3;
16 class gtsam::Pose3;
17 virtual class gtsam::noiseModel::Base;
18 virtual class gtsam::noiseModel::Gaussian;
19 virtual class gtsam::imuBias::ConstantBias;
20 virtual class gtsam::NonlinearFactor;
21 virtual class gtsam::NoiseModelFactor;
22 virtual class gtsam::NoiseModelFactor2;
23 virtual class gtsam::NoiseModelFactor3;
24 virtual class gtsam::NoiseModelFactor4;
25 virtual class gtsam::GaussianFactor;
26 virtual class gtsam::HessianFactor;
27 virtual class gtsam::JacobianFactor;
28 class gtsam::Cal3_S2;
29 class gtsam::Cal3DS2;
32 class gtsam::Ordering;
33 class gtsam::Values;
34 class gtsam::Key;
36 class gtsam::KeyList;
37 class gtsam::KeySet;
38 class gtsam::KeyVector;
40 class gtsam::ISAM2Params;
42 
43 namespace gtsam {
44 
46 class Dummy {
47  Dummy();
48  void print(string s) const;
49  unsigned char dummyTwoVar(unsigned char a) const;
50 };
51 
53 class PoseRTV {
54  PoseRTV();
55  PoseRTV(Vector rtv);
56  PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const Vector& vel);
57  PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const Vector& vel);
58  PoseRTV(const gtsam::Pose3& pose, const Vector& vel);
59  PoseRTV(const gtsam::Pose3& pose);
60  PoseRTV(double roll, double pitch, double yaw, double x, double y, double z, double vx, double vy, double vz);
61 
62  // testable
63  bool equals(const gtsam::PoseRTV& other, double tol) const;
64  void print(string s) const;
65 
66  // access
67  gtsam::Point3 translation() const;
68  gtsam::Rot3 rotation() const;
69  Vector velocity() const;
70  gtsam::Pose3 pose() const;
71 
72  // Vector interfaces
73  Vector vector() const;
74  Vector translationVec() const;
75  Vector velocityVec() const;
76 
77  // manifold/Lie
78  static size_t Dim();
79  size_t dim() const;
80  gtsam::PoseRTV retract(Vector v) const;
81  Vector localCoordinates(const gtsam::PoseRTV& p) const;
82  static gtsam::PoseRTV Expmap(Vector v);
83  static Vector Logmap(const gtsam::PoseRTV& p);
84  gtsam::PoseRTV inverse() const;
85  gtsam::PoseRTV compose(const gtsam::PoseRTV& p) const;
86  gtsam::PoseRTV between(const gtsam::PoseRTV& p) const;
87 
88  // measurement
89  double range(const gtsam::PoseRTV& other) const;
91 
92  // IMU/dynamics
93  gtsam::PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const;
94  gtsam::PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const;
95  gtsam::PoseRTV generalDynamics(Vector accel, Vector gyro, double dt) const;
96  Vector imuPrediction(const gtsam::PoseRTV& x2, double dt) const;
97  gtsam::Point3 translationIntegration(const gtsam::PoseRTV& x2, double dt) const;
98  Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const;
99 
100  void serializable() const; // enabling serialization functionality
101 };
102 
103 #include <gtsam_unstable/geometry/Pose3Upright.h>
105  Pose3Upright();
106  Pose3Upright(const gtsam::Pose3Upright& other);
107  Pose3Upright(const gtsam::Rot2& bearing, const gtsam::Point3& t);
108  Pose3Upright(double x, double y, double z, double theta);
109  Pose3Upright(const gtsam::Pose2& pose, double z);
110 
111  void print(string s) const;
112  bool equals(const gtsam::Pose3Upright& pose, double tol) const;
113 
114  double x() const;
115  double y() const;
116  double z() const;
117  double theta() const;
118 
119  gtsam::Point2 translation2() const;
120  gtsam::Point3 translation() const;
121  gtsam::Rot2 rotation2() const;
122  gtsam::Rot3 rotation() const;
123  gtsam::Pose2 pose2() const;
124  gtsam::Pose3 pose() const;
125 
126  size_t dim() const;
127  gtsam::Pose3Upright retract(Vector v) const;
128  Vector localCoordinates(const gtsam::Pose3Upright& p2) const;
129 
130  static gtsam::Pose3Upright identity();
131  gtsam::Pose3Upright inverse() const;
132  gtsam::Pose3Upright compose(const gtsam::Pose3Upright& p2) const;
133  gtsam::Pose3Upright between(const gtsam::Pose3Upright& p2) const;
134 
135  static gtsam::Pose3Upright Expmap(Vector xi);
136  static Vector Logmap(const gtsam::Pose3Upright& p);
137 
138  void serializable() const; // enabling serialization functionality
139 }; // \class Pose3Upright
140 
141 #include <gtsam_unstable/geometry/BearingS2.h>
142 class BearingS2 {
143  BearingS2();
144  BearingS2(double azimuth_double, double elevation_double);
145  BearingS2(const gtsam::Rot2& azimuth, const gtsam::Rot2& elevation);
146 
147  gtsam::Rot2 azimuth() const;
148  gtsam::Rot2 elevation() const;
149 
150  static gtsam::BearingS2 fromDownwardsObservation(const gtsam::Pose3& A, const gtsam::Point3& B);
151  static gtsam::BearingS2 fromForwardObservation(const gtsam::Pose3& A, const gtsam::Point3& B);
152 
153  void print(string s) const;
154  bool equals(const gtsam::BearingS2& x, double tol) const;
155 
156  size_t dim() const;
157  gtsam::BearingS2 retract(Vector v) const;
158  Vector localCoordinates(const gtsam::BearingS2& p2) const;
159 
160  void serializable() const; // enabling serialization functionality
161 };
162 
163 #include <gtsam_unstable/geometry/SimWall2D.h>
164 class SimWall2D {
165  SimWall2D();
166  SimWall2D(const gtsam::Point2& a, const gtsam::Point2& b);
167  SimWall2D(double ax, double ay, double bx, double by);
168 
169  void print(string s) const;
170  bool equals(const gtsam::SimWall2D& other, double tol) const;
171 
172  gtsam::Point2 a() const;
173  gtsam::Point2 b() const;
174 
175  gtsam::SimWall2D scale(double s) const;
176  double length() const;
177  gtsam::Point2 midpoint() const;
178 
179  bool intersects(const gtsam::SimWall2D& wall) const;
180  // bool intersects(const gtsam::SimWall2D& wall, boost::optional<gtsam::Point2&> pt=boost::none) const;
181 
182  gtsam::Point2 norm() const;
183  gtsam::Rot2 reflection(const gtsam::Point2& init, const gtsam::Point2& intersection) const;
184 };
185 
186 #include <gtsam_unstable/geometry/SimPolygon2D.h>
188  static void seedGenerator(size_t seed);
189  static gtsam::SimPolygon2D createTriangle(const gtsam::Point2& pA, const gtsam::Point2& pB, const gtsam::Point2& pC);
190  static gtsam::SimPolygon2D createRectangle(const gtsam::Point2& p, double height, double width);
191 
192  static gtsam::SimPolygon2D randomTriangle(double side_len, double mean_side_len, double sigma_side_len,
193  double min_vertex_dist, double min_side_len, const gtsam::SimPolygon2DVector& existing_polys);
194  static gtsam::SimPolygon2D randomRectangle(double side_len, double mean_side_len, double sigma_side_len,
195  double min_vertex_dist, double min_side_len, const gtsam::SimPolygon2DVector& existing_polys);
196 
197  gtsam::Point2 landmark(size_t i) const;
198  size_t size() const;
199  gtsam::Point2Vector vertices() const;
200 
201  bool equals(const gtsam::SimPolygon2D& p, double tol) const;
202  void print(string s) const;
203 
204  gtsam::SimWall2DVector walls() const;
205  bool contains(const gtsam::Point2& p) const;
206  bool overlaps(const gtsam::SimPolygon2D& p) const;
207 
208  static bool anyContains(const gtsam::Point2& p, const gtsam::SimPolygon2DVector& obstacles);
209  static bool anyOverlaps(const gtsam::SimPolygon2D& p, const gtsam::SimPolygon2DVector& obstacles);
210  static bool insideBox(double s, const gtsam::Point2& p);
211  static bool nearExisting(const gtsam::Point2Vector& S,
212  const gtsam::Point2& p, double threshold);
213 
214  static gtsam::Point2 randomPoint2(double s);
215  static gtsam::Rot2 randomAngle();
216  static double randomDistance(double mu, double sigma);
217  static double randomDistance(double mu, double sigma, double min_dist);
218  static gtsam::Point2 randomBoundedPoint2(double boundary_size,
219  const gtsam::Point2Vector& landmarks, double min_landmark_dist);
220  static gtsam::Point2 randomBoundedPoint2(double boundary_size,
221  const gtsam::Point2Vector& landmarks,
222  const gtsam::SimPolygon2DVector& obstacles, double min_landmark_dist);
223  static gtsam::Point2 randomBoundedPoint2(double boundary_size,
224  const gtsam::SimPolygon2DVector& obstacles);
225  static gtsam::Point2 randomBoundedPoint2(
226  const gtsam::Point2& LL_corner, const gtsam::Point2& UR_corner,
227  const gtsam::Point2Vector& landmarks,
228  const gtsam::SimPolygon2DVector& obstacles, double min_landmark_dist);
229  static gtsam::Pose2 randomFreePose(double boundary_size, const gtsam::SimPolygon2DVector& obstacles);
230  };
231 
232  // std::vector<gtsam::SimWall2D>
234  {
235  //Capacity
236  size_t size() const;
237  size_t max_size() const;
238  void resize(size_t sz);
239  size_t capacity() const;
240  bool empty() const;
241  void reserve(size_t n);
242 
243  //Element access
244  gtsam::SimWall2D at(size_t n) const;
245  gtsam::SimWall2D front() const;
246  gtsam::SimWall2D back() const;
247 
248  //Modifiers
249  void assign(size_t n, const gtsam::SimWall2D& u);
250  void push_back(const gtsam::SimWall2D& x);
251  void pop_back();
252  };
253 
254  // std::vector<gtsam::SimPolygon2D>
256  {
257  //Capacity
258  size_t size() const;
259  size_t max_size() const;
260  void resize(size_t sz);
261  size_t capacity() const;
262  bool empty() const;
263  void reserve(size_t n);
264 
265  //Element access
266  gtsam::SimPolygon2D at(size_t n) const;
267  gtsam::SimPolygon2D front() const;
268  gtsam::SimPolygon2D back() const;
269 
270  //Modifiers
271  void assign(size_t n, const gtsam::SimPolygon2D& u);
272  void push_back(const gtsam::SimPolygon2D& x);
273  void pop_back();
274  };
275 
276 // Nonlinear factors from gtsam, for our Value types
277 #include <gtsam/slam/PriorFactor.h>
278 template<T = {gtsam::PoseRTV}>
279 virtual class PriorFactor : gtsam::NoiseModelFactor {
280  PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
281 
282  void serializable() const; // enabling serialization functionality
283 };
284 
285 
287 template<T = {gtsam::PoseRTV}>
288 virtual class BetweenFactor : gtsam::NoiseModelFactor {
289  BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
290 
291  void serializable() const; // enabling serialization functionality
292 };
293 
295 template<T = {gtsam::Pose2}>
296 virtual class BetweenFactorEM : gtsam::NonlinearFactor {
297  BetweenFactorEM(size_t key1, size_t key2, const T& relativePose,
298  const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
299  double prior_inlier, double prior_outlier);
300 
301  BetweenFactorEM(size_t key1, size_t key2, const T& relativePose,
302  const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
303  double prior_inlier, double prior_outlier, bool flag_bump_up_near_zero_probs);
304 
305  Vector whitenedError(const gtsam::Values& x);
306  Vector unwhitenedError(const gtsam::Values& x);
307  Vector calcIndicatorProb(const gtsam::Values& x);
308  gtsam::Pose2 measured(); // TODO: figure out how to output a template instead
309  void set_flag_bump_up_near_zero_probs(bool flag);
310  bool get_flag_bump_up_near_zero_probs() const;
311 
312  void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph);
313  void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12);
314  Matrix get_model_inlier_cov();
315  Matrix get_model_outlier_cov();
316 
317  void serializable() const; // enabling serialization functionality
318 };
319 
321 template<T = {gtsam::Pose2}>
322 virtual class TransformBtwRobotsUnaryFactorEM : gtsam::NonlinearFactor {
323  TransformBtwRobotsUnaryFactorEM(size_t key, const T& relativePose, size_t keyA, size_t keyB,
324  const gtsam::Values& valA, const gtsam::Values& valB,
325  const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
326  double prior_inlier, double prior_outlier);
327 
328  TransformBtwRobotsUnaryFactorEM(size_t key, const T& relativePose, size_t keyA, size_t keyB,
329  const gtsam::Values& valA, const gtsam::Values& valB,
330  const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
331  double prior_inlier, double prior_outlier, bool flag_bump_up_near_zero_probs, bool start_with_M_step);
332 
333  Vector whitenedError(const gtsam::Values& x);
334  Vector unwhitenedError(const gtsam::Values& x);
335  Vector calcIndicatorProb(const gtsam::Values& x);
336  void setValAValB(const gtsam::Values valA, const gtsam::Values valB);
337 
338  void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph);
339  void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12);
340  Matrix get_model_inlier_cov();
341  Matrix get_model_outlier_cov();
342 
343  void serializable() const; // enabling serialization functionality
344 };
345 
347 template<T = {gtsam::Pose2}>
348 virtual class TransformBtwRobotsUnaryFactor : gtsam::NonlinearFactor {
349  TransformBtwRobotsUnaryFactor(size_t key, const T& relativePose, size_t keyA, size_t keyB,
350  const gtsam::Values& valA, const gtsam::Values& valB,
351  const gtsam::noiseModel::Gaussian* model);
352 
353  Vector whitenedError(const gtsam::Values& x);
354  Vector unwhitenedError(const gtsam::Values& x);
355  void setValAValB(const gtsam::Values valA, const gtsam::Values valB);
356 
357  void serializable() const; // enabling serialization functionality
358 };
359 
361 virtual class SmartRangeFactor : gtsam::NoiseModelFactor {
362  SmartRangeFactor(double s);
363 
364  void addRange(size_t key, double measuredRange);
365  gtsam::Point2 triangulate(const gtsam::Values& x) const;
366  //void print(string s) const;
367 
368 };
369 
370 #include <gtsam/sam/RangeFactor.h>
371 template<POSE, POINT>
372 virtual class RangeFactor : gtsam::NoiseModelFactor {
373  RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
374 
375  void serializable() const; // enabling serialization functionality
376 };
377 
379 
380 
381 #include <gtsam/nonlinear/NonlinearEquality.h>
382 template<T = {gtsam::PoseRTV}>
383 virtual class NonlinearEquality : gtsam::NoiseModelFactor {
384  // Constructor - forces exact evaluation
385  NonlinearEquality(size_t j, const T& feasible);
386  // Constructor - allows inexact evaluation
387  NonlinearEquality(size_t j, const T& feasible, double error_gain);
388 
389  void serializable() const; // enabling serialization functionality
390 };
391 
392 #include <gtsam_unstable/dynamics/IMUFactor.h>
393 template<POSE = {gtsam::PoseRTV}>
394 virtual class IMUFactor : gtsam::NoiseModelFactor {
396  IMUFactor(Vector accel, Vector gyro,
397  double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
398 
400  IMUFactor(Vector imu_vector,
401  double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
402 
403  Vector gyro() const;
404  Vector accel() const;
405  Vector z() const;
406  size_t key1() const;
407  size_t key2() const;
408 };
409 
411 template<POSE = {gtsam::PoseRTV}>
412 virtual class FullIMUFactor : gtsam::NoiseModelFactor {
414  FullIMUFactor(Vector accel, Vector gyro,
415  double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
416 
418  FullIMUFactor(Vector imu,
419  double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
420 
421  Vector gyro() const;
422  Vector accel() const;
423  Vector z() const;
424  size_t key1() const;
425  size_t key2() const;
426 };
427 
429 virtual class DHeightPrior : gtsam::NonlinearFactor {
430  DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model);
431 };
432 
433 virtual class DRollPrior : gtsam::NonlinearFactor {
435  DRollPrior(size_t key, double wx, const gtsam::noiseModel::Base* model);
437  DRollPrior(size_t key, const gtsam::noiseModel::Base* model);
438 };
439 
440 virtual class VelocityPrior : gtsam::NonlinearFactor {
441  VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model);
442 };
443 
444 virtual class DGroundConstraint : gtsam::NonlinearFactor {
445  // Primary constructor allows for variable height of the "floor"
446  DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model);
447  // Fully specify vector - use only for debugging
448  DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model);
449 };
450 
451 #include <gtsam/base/deprecated/LieScalar.h>
452 
454 virtual class VelocityConstraint3 : gtsam::NonlinearFactor {
456  VelocityConstraint3(size_t key1, size_t key2, size_t velKey, double dt);
457 
458  Vector evaluateError(const gtsam::LieScalar& x1, const gtsam::LieScalar& x2, const gtsam::LieScalar& v) const;
459 };
460 
462 virtual class PendulumFactor1 : gtsam::NonlinearFactor {
464  PendulumFactor1(size_t k1, size_t k, size_t velKey, double dt);
465 
466  Vector evaluateError(const gtsam::LieScalar& qk1, const gtsam::LieScalar& qk, const gtsam::LieScalar& v) const;
467 };
468 
470 virtual class PendulumFactor2 : gtsam::NonlinearFactor {
472  PendulumFactor2(size_t vk1, size_t vk, size_t qKey, double dt, double L, double g);
473 
474  Vector evaluateError(const gtsam::LieScalar& vk1, const gtsam::LieScalar& vk, const gtsam::LieScalar& q) const;
475 };
476 
477 virtual class PendulumFactorPk : gtsam::NonlinearFactor {
479  PendulumFactorPk(size_t pk, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha);
480 
481  Vector evaluateError(const gtsam::LieScalar& pk, const gtsam::LieScalar& qk, const gtsam::LieScalar& qk1) const;
482 };
483 
484 virtual class PendulumFactorPk1 : gtsam::NonlinearFactor {
486  PendulumFactorPk1(size_t pk1, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha);
487 
488  Vector evaluateError(const gtsam::LieScalar& pk1, const gtsam::LieScalar& qk, const gtsam::LieScalar& qk1) const;
489 };
490 
491 #include <gtsam_unstable/dynamics/SimpleHelicopter.h>
492 virtual class Reconstruction : gtsam::NoiseModelFactor {
493  Reconstruction(size_t gKey1, size_t gKey, size_t xiKey, double h);
494 
495  Vector evaluateError(const gtsam::Pose3& gK1, const gtsam::Pose3& gK, Vector xiK) const;
496 };
497 
498 virtual class DiscreteEulerPoincareHelicopter : gtsam::NoiseModelFactor {
499  DiscreteEulerPoincareHelicopter(size_t xiKey, size_t xiKey_1, size_t gKey,
500  double h, Matrix Inertia, Vector Fu, double m);
501 
502  Vector evaluateError(Vector xiK, Vector xiK_1, const gtsam::Pose3& gK) const;
503 };
504 
505 //*************************************************************************
506 // nonlinear
507 //*************************************************************************
510  FixedLagSmootherKeyTimestampMapValue(size_t key, double timestamp);
512 };
513 
517 
518  // Note: no print function
519 
520  // common STL methods
521  size_t size() const;
522  bool empty() const;
523  void clear();
524 
525  double at(const size_t key) const;
526  void insert(const gtsam::FixedLagSmootherKeyTimestampMapValue& value);
527 };
528 
530  size_t getIterations() const;
531  size_t getNonlinearVariables() const;
532  size_t getLinearVariables() const;
533  double getError() const;
534 };
535 
537 virtual class FixedLagSmoother {
538  void print(string s) const;
539  bool equals(const gtsam::FixedLagSmoother& rhs, double tol) const;
540 
542  double smootherLag() const;
543 
546 };
547 
549 virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
550  BatchFixedLagSmoother();
551  BatchFixedLagSmoother(double smootherLag);
552  BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params);
553 
555  template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
557  Vector, Matrix}>
558  VALUE calculateEstimate(size_t key) const;
559 };
560 
562 virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother {
566 
567  gtsam::ISAM2Params params() const;
568 };
569 
571 virtual class ConcurrentFilter {
572  void print(string s) const;
573  bool equals(const gtsam::ConcurrentFilter& rhs, double tol) const;
574 };
575 
576 virtual class ConcurrentSmoother {
577  void print(string s) const;
578  bool equals(const gtsam::ConcurrentSmoother& rhs, double tol) const;
579 };
580 
581 // Synchronize function
582 void synchronize(gtsam::ConcurrentFilter& filter, gtsam::ConcurrentSmoother& smoother);
583 
586  size_t getIterations() const;
587  size_t getLambdas() const;
588  size_t getNonlinearVariables() const;
589  size_t getLinearVariables() const;
590  double getError() const;
591 };
592 
596 
601 
604  gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
605  gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyList& keysToMove);
607 };
608 
611  size_t getIterations() const;
612  size_t getLambdas() const;
613  size_t getNonlinearVariables() const;
614  size_t getLinearVariables() const;
615  double getError() const;
616 };
617 
621 
626 
629  gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
631 };
632 
633 //*************************************************************************
634 // slam
635 //*************************************************************************
637 virtual class RelativeElevationFactor: gtsam::NoiseModelFactor {
638  RelativeElevationFactor();
639  RelativeElevationFactor(size_t poseKey, size_t pointKey, double measured,
640  const gtsam::noiseModel::Base* model);
641 
642  double measured() const;
643  //void print(string s) const;
644 };
645 
647 virtual class DummyFactor : gtsam::NonlinearFactor {
648  DummyFactor(size_t key1, size_t dim1, size_t key2, size_t dim2);
649 };
650 
652 virtual class InvDepthFactorVariant1 : gtsam::NoiseModelFactor {
653  InvDepthFactorVariant1(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
654 };
655 
657 virtual class InvDepthFactorVariant2 : gtsam::NoiseModelFactor {
658  InvDepthFactorVariant2(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::Point3& referencePoint, const gtsam::noiseModel::Base* model);
659 };
660 
662 virtual class InvDepthFactorVariant3a : gtsam::NoiseModelFactor {
663  InvDepthFactorVariant3a(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
664 };
665 virtual class InvDepthFactorVariant3b : gtsam::NoiseModelFactor {
666  InvDepthFactorVariant3b(size_t poseKey1, size_t poseKey2, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
667 };
668 
669 
670 #include <gtsam_unstable/slam/Mechanization_bRn2.h>
671 class Mechanization_bRn2 {
673  Mechanization_bRn2(gtsam::Rot3& initial_bRn, Vector initial_x_g,
674  Vector initial_x_a);
675  Vector b_g(double g_e);
676  gtsam::Rot3 bRn();
677  Vector x_g();
678  Vector x_a();
679  static gtsam::Mechanization_bRn2 initialize(Matrix U, Matrix F, double g_e);
680  gtsam::Mechanization_bRn2 correct(Vector dx) const;
681  gtsam::Mechanization_bRn2 integrate(Vector u, double dt) const;
682  //void print(string s) const;
683 };
684 
685 #include <gtsam_unstable/slam/AHRS.h>
686 class AHRS {
687  AHRS(Matrix U, Matrix F, double g_e);
688  pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> initialize(double g_e);
689  pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> integrate(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector u, double dt);
690  pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aid(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, bool Farrel);
691  pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aidGeneral(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, Vector f_expected, const gtsam::Rot3& increment);
692  //void print(string s) const;
693 };
694 
695 // Tectonic SAM Factors
696 
698 //typedef gtsam::NoiseModelFactor2<gtsam::Pose2, gtsam::Point2> NLPosePose;
699 virtual class DeltaFactor : gtsam::NoiseModelFactor {
700  DeltaFactor(size_t i, size_t j, const gtsam::Point2& measured,
702  //void print(string s) const;
703 };
704 
705 //typedef gtsam::NoiseModelFactor4<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2,
706 // gtsam::Point2> NLPosePosePosePoint;
707 virtual class DeltaFactorBase : gtsam::NoiseModelFactor {
708  DeltaFactorBase(size_t b1, size_t i, size_t b2, size_t j,
709  const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel);
710  //void print(string s) const;
711 };
712 
713 //typedef gtsam::NoiseModelFactor4<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2,
714 // gtsam::Pose2> NLPosePosePosePose;
715 virtual class OdometryFactorBase : gtsam::NoiseModelFactor {
716  OdometryFactorBase(size_t b1, size_t i, size_t b2, size_t j,
717  const gtsam::Pose2& measured, const gtsam::noiseModel::Base* noiseModel);
718  //void print(string s) const;
719 };
720 
721 #include <gtsam/geometry/Cal3DS2.h>
723 template<POSE, LANDMARK, CALIBRATION>
724 virtual class ProjectionFactorPPP : gtsam::NoiseModelFactor {
726  size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k);
727 
729  size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality);
730 
731  gtsam::Point2 measured() const;
732  CALIBRATION* calibration() const;
733  bool verboseCheirality() const;
734  bool throwCheirality() const;
735 
736  // enabling serialization functionality
737  void serialize() const;
738 };
741 
742 
744 template<POSE, LANDMARK, CALIBRATION>
745 virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor {
747  size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey);
748 
750  size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey, bool throwCheirality, bool verboseCheirality);
751 
752  gtsam::Point2 measured() const;
753  bool verboseCheirality() const;
754  bool throwCheirality() const;
755 
756  // enabling serialization functionality
757  void serialize() const;
758 };
761 
762 } //\namespace gtsam
An iSAM2-based fixed-lag smoother.
Derived from ProjectionFactor, but estimates body-camera transform and calibration in addition to bod...
Values calculateEstimate() const
Compute the current best estimate of all variables and return a full Values structure.
Definition: ConcurrentBatchSmoother.h:91
A simple factor that can be used to trick gtsam solvers into believing a graph is connected.
virtual void print(const std::string &s="Concurrent Filter:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const =0
Implement a standard 'print' function.
Inverse Depth Factor based on Civera09tro, Montiel06rss.
noiseModel::Base is the abstract base class for all noise models.
Definition: NoiseModel.h:51
Mechanization_bRn2 correct(const Vector9 &dx) const
Correct AHRS full state given error state dx.
Definition: Mechanization_bRn2.cpp:68
PendulumFactorPk1()
default constructor to allow for serialization
Definition: Pendulum.h:179
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:345
const Values & getLinearizationPoint() const
Access the current linearization point.
Definition: ConcurrentBatchFilter.h:81
Mechanization_bRn2 integrate(const Vector3 &u, const double dt) const
Integrate to get new state.
Definition: Mechanization_bRn2.cpp:81
Vector evaluateError(const double &x1, const double &x2, const double &v, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
x1 + v*dt - x2 = 0, with optional derivatives
Definition: VelocityConstraint3.h:39
The interface for the 'Filter' portion of the Concurrent Filtering and Smoother architecture.
Definition: ConcurrentFilteringAndSmoothing.h:39
Definition: gtsam_unstable.h:142
Point2 triangulate(const Values &x) const
Triangulate a point from at least three pose-range pairs Checks for best pair that includes first poi...
Definition: SmartRangeFactor.h:91
Definition: gtsam_unstable.h:610
TransformBtwRobotsUnaryFactor()
default constructor - only use for serialization
Definition: TransformBtwRobotsUnaryFactor.h:67
const T & measured() const
return the measurement
Definition: ExpressionFactor.h:67
Definition: Cal3DS2.h:32
This is the base class for any type to be stored in Values.
Definition: Value.h:36
DRollPrior(Key key, double wx, const gtsam::SharedNoiseModel &model)
allows for explicit roll parameterization - uses canonical coordinate
Definition: DynamicsPriors.h:37
const Point2 & measured() const
return the measurement
Definition: ProjectionFactorPPP.h:154
Definition: Point3.h:45
DeltaFactor(Key i, Key j, const Point2 &measured, const SharedNoiseModel &model)
Constructor.
Definition: TSAMFactors.h:42
Robot state for use with IMU measurements.
Definition: PoseRTV.h:23
OdometryFactorBase(Key b1, Key i, Key b2, Key j, const Pose2 &measured, const SharedNoiseModel &model)
Constructor.
Definition: TSAMFactors.h:126
Definition: RangeFactor.h:35
A Gaussian density.
Definition: GaussianDensity.h:33
Definition: gtsam_unstable.h:509
IncrementalFixedLagSmoother(double smootherLag=0.0, const ISAM2Params &parameters=ISAM2Params())
default constructor
Definition: IncrementalFixedLagSmoother.h:41
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
bool verboseCheirality() const
return verbosity
Definition: ProjectionFactorPPP.h:164
double smootherLag() const
read the current smoother lag
Definition: FixedLagSmoother.h:78
Definition: FixedLagSmoother.h:33
PendulumFactor2()
default constructor to allow for serialization
Definition: Pendulum.h:76
Definition: gtsam_unstable.h:585
Template to create a binary predicate.
Definition: Testable.h:110
Definition: Mechanization_bRn2.h:17
std::pair< Mechanization_bRn2, KalmanFilter::State > aid(const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, bool Farrell=0) const
Aid the AHRS with an accelerometer reading, typically called when isAidingAvailable == true.
Definition: AHRS.cpp:159
const VectorValues & getDelta() const
Access the current set of deltas to the linearization point.
Definition: ConcurrentBatchSmoother.h:84
Dummy class for testing MATLAB memory allocation.
virtual bool equals(const FixedLagSmoother &rhs, double tol=1e-9) const
Check if two IncrementalFixedLagSmoother Objects are equal.
Definition: FixedLagSmoother.cpp:40
DGroundConstraint(Key key, double height, const gtsam::SharedNoiseModel &model)
Primary constructor allows for variable height of the "floor".
Definition: DynamicsPriors.h:76
SmartRangeFactor()
Default constructor: don't use directly.
Definition: SmartRangeFactor.h:47
A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoother interface.
Definition: ConcurrentBatchSmoother.h:31
Inverse Depth Factor based on Civera09tro, Montiel06rss.
const Point3 & referencePoint() const
return the calibration object
Definition: InvDepthFactorVariant2.h:135
A Linear Factor Graph is a factor graph where all factors are Gaussian, i.e.
Definition: GaussianFactorGraph.h:65
A Levenberg-Marquardt Batch Filter that implements the Concurrent Filtering and Smoother interface.
Definition: ConcurrentBatchFilter.h:31
A simple 3-way factor constraining double poses and velocity.
void addRange(Key key, double measuredRange)
Add a range measurement to a pose with given key.
Definition: SmartRangeFactor.h:62
NonlinearEquality()
default constructor - only for serialization
Definition: NonlinearEquality.h:77
InvDepthFactorVariant1()
Default constructor.
Definition: InvDepthFactorVariant1.h:44
ProjectionFactorPPPC()
Default constructor.
Definition: ProjectionFactorPPPC.h:55
Gaussian implements the mathematical model |R*x|^2 = |y|^2 with R'*R=inv(Sigma) where y = whiten(x) =...
Definition: NoiseModel.h:141
An abstract virtual base class for JacobianFactor and HessianFactor.
Definition: GaussianFactor.h:38
Pose3 with translational velocity.
const VectorValues & getDelta() const
Access the current set of deltas to the linearization point.
Definition: ConcurrentBatchFilter.h:91
const KeyTimestampMap & timestamps() const
Access the current set of timestamps associated with each variable.
Definition: FixedLagSmoother.h:88
Base class for a fixed-lag smoother.
Definition: Rot3.h:56
BetweenFactor()
default constructor - only use for serialization
Definition: BetweenFactor.h:55
DummyFactor()
Default constructor: don't use directly.
Definition: DummyFactor.h:27
Vector evaluateError(const double &vk1, const double &vk, const double &q, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
v_k - h*g/L*sin(q) - v_k1 = 0, with optional derivatives
Definition: Pendulum.h:96
Factor to express an IMU measurement between dynamic poses.
Definition: ProjectionFactorPPP.h:34
A convenient base class for creating your own NoiseModelFactor with 4 variables.
Definition: NonlinearFactor.h:497
Definition: ISAM2Params.h:135
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition: ProjectionFactorPPP.h:167
const LevenbergMarquardtParams & params() const
read the current set of optimizer parameters
Definition: BatchFixedLagSmoother.h:76
double measured() const
return the measured
Definition: RelativeElevationFactor.h:55
A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoothing interface...
virtual void print(const std::string &s="Concurrent Smoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const =0
Implement a standard 'print' function.
Definition: gtsam_unstable.h:187
Definition: FastList.h:38
Definition: ImuBias.h:30
const ISAM2Params & params() const
return the current set of iSAM2 parameters
Definition: IncrementalFixedLagSmoother.h:89
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
double range(const PoseRTV &other, OptionalJacobian< 1, 9 > H1=boost::none, OptionalJacobian< 1, 9 > H2=boost::none) const
range between translations
Definition: PoseRTV.cpp:169
DeltaFactorBase(Key b1, Key i, Key b2, Key j, const Point2 &measured, const SharedNoiseModel &model)
Constructor.
Definition: TSAMFactors.h:71
Definition: gtsam_unstable.h:104
Point3 translationIntegration(const Rot3 &r2, const Velocity3 &v2, double dt) const
predict measurement and where Point3 for x2 should be, as a way of enforcing a velocity constraint Th...
Definition: PoseRTV.cpp:161
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:210
const Values & getLinearizationPoint() const
Access the current linearization point.
Definition: ConcurrentBatchSmoother.h:74
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:377
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap &timestamps=KeyTimestampMap(), const FastVector< size_t > &factorsToRemove=FastVector< size_t >())=0
Add new factors, updating the solution and relinearizing as needed.
Mechanization_bRn2(const Rot3 &initial_bRn=Rot3(), const Vector3 &initial_x_g=Z_3x1, const Vector3 &initial_x_a=Z_3x1)
Constructor.
Definition: Mechanization_bRn2.h:32
Unary factor for determining transformation between given trajectories of two robots.
This class represents a collection of vector-valued variables associated each with a unique integer i...
Definition: VectorValues.h:73
Vector evaluateError(const Vector6 &xik, const Vector6 &xik_1, const Pose3 &gk, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
DEP, with optional derivatives pk - pk_1 - h_*Fu_ - h_*f_ext = 0 where pk = CT_TLN(h*xi_k)*Inertia*xi...
Definition: SimpleHelicopter.h:110
Parameters for Levenberg-Marquardt optimization.
Definition: LevenbergMarquardtParams.h:33
virtual void print(const std::string &s="FixedLagSmoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Print the factor for debugging and testing (implementing Testable)
Definition: FixedLagSmoother.cpp:34
void setValAValB(const Values &valA, const Values &valB)
implement functions needed to derive from Factor
Definition: TransformBtwRobotsUnaryFactorEM.h:137
Definition: gtsam_unstable.h:529
Three-way factors for the pendulum dynamics as in [Stern06siggraph] for (1) explicit Euler method,...
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:420
Definition: Rot2.h:33
Definition: gtsam_unstable.h:255
virtual bool equals(const ConcurrentSmoother &rhs, double tol=1e-9) const =0
Check if two Concurrent Smoothers are equal.
The interface for the 'Smoother' portion of the Concurrent Filtering and Smoother architecture.
Definition: ConcurrentFilteringAndSmoothing.h:99
A nonlinear sum-of-squares factor with a zero-mean noise model implementing the density Templated on...
Definition: NonlinearFactor.h:161
Definition: gtsam_unstable.h:164
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
virtual bool equals(const ConcurrentFilter &rhs, double tol=1e-9) const =0
Check if two Concurrent Smoothers are equal.
InvDepthFactorVariant2()
Default constructor.
Definition: InvDepthFactorVariant2.h:46
Vector3 b_g(double g_e) const
gravity in the body frame
Definition: Mechanization_bRn2.h:43
Definition: Pose2.h:36
ProjectionFactorPPP()
Default constructor.
Definition: ProjectionFactorPPP.h:57
void setValAValB(const gtsam::Values &valA, const gtsam::Values &valB)
implement functions needed to derive from Factor
Definition: TransformBtwRobotsUnaryFactor.h:114
Values calculateEstimate() const
Compute an estimate from the incomplete linear delta computed during the last update.
Definition: BatchFixedLagSmoother.h:59
PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const
Dynamics integrator for ground robots Always move from time 1 to time 2.
Definition: PoseRTV.cpp:60
PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const
Simulates flying robot with simple flight model Integrates state x1 -> x2 given controls x1 = {p1,...
Definition: PoseRTV.cpp:85
Priors to be used with dynamic systems (Specifically PoseRTV)
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:77
const Ordering & getOrdering() const
Access the current ordering.
Definition: ConcurrentBatchSmoother.h:79
Definition: Point2.h:40
const NonlinearFactorGraph & getFactors() const
Access the current set of factors.
Definition: ConcurrentBatchFilter.h:76
Vector evaluateError(const double &pk1, const double &qk, const double &qk1, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
1/h mr^2 (qk1-qk) - mgrh a sin((1-a)pk + a*pk1) - pk1 = 0, with optional derivatives
Definition: Pendulum.h:203
A Gaussian factor in the squared-error form.
Definition: JacobianFactor.h:87
Definition: gtsam_unstable.h:514
static Mechanization_bRn2 initialize(const Matrix &U, const Matrix &F, const double g_e=0, bool flat=false)
Matrix version of initialize.
Definition: Mechanization_bRn2.cpp:23
virtual Values calculateEstimate() const =0
Compute an estimate from the incomplete linear delta computed during the last update.
Vector evaluateError(const double &qk1, const double &qk, const double &v, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
q_k + h*v - q_k1 = 0, with optional derivatives
Definition: Pendulum.h:48
Definition: gtsam_unstable.h:233
Vector6 imuPrediction(const PoseRTV &x2, double dt) const
Dynamics predictor for both ground and flying robots, given states at 1 and 2 Always move from time 1...
Definition: PoseRTV.cpp:133
TSAM 1 Factors, simpler than the hierarchical TSAM 2.
Base classes for the 'filter' and 'smoother' portion of the Concurrent Filtering and Smoothing archit...
PriorFactor()
default constructor - only use for serialization
Definition: PriorFactor.h:51
Definition: Cal3_S2.h:33
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition: ProjectionFactorPPPC.h:158
A Levenberg-Marquardt Batch Filter that implements the Concurrent Filtering and Smoothing interface.
const NonlinearFactorGraph & getFactors() const
Access the current set of factors.
Definition: ConcurrentBatchSmoother.h:69
PendulumFactor1()
default constructor to allow for serialization
Definition: Pendulum.h:30
RangeFactor()
default constructor
Definition: RangeFactor.h:42
Factor representing a known relative altitude in global frame.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Key key1() const
methods to retrieve keys
Definition: NonlinearFactor.h:454
Vector translationIntegrationVec(const PoseRTV &x2, double dt) const
Definition: PoseRTV.h:128
InvDepthFactorVariant3b()
Default constructor.
Definition: InvDepthFactorVariant3.h:164
IMUFactor(const Vector3 &accel, const Vector3 &gyro, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
time between measurements
Definition: IMUFactor.h:35
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Derived from ProjectionFactor, but estimates body-camera transform in addition to body pose and 3D la...
const Point2 & measured() const
return the measurement
Definition: ProjectionFactorPPPC.h:150
Matrix trans(const Matrix &A)
static transpose function, just calls Eigen transpose member function
Definition: Matrix.h:244
Unary factor for determining transformation between given trajectories of two robots.
AHRS(const Matrix &stationaryU, const Matrix &stationaryF, double g_e, bool flat=false)
AHRS constructor.
Definition: AHRS.cpp:24
A smart factor for range-only SLAM that does initialization and marginalization.
An LM-based fixed-lag smoother.
PoseRTV generalDynamics(const Vector &accel, const Vector &gyro, double dt) const
General Dynamics update - supply control inputs in body frame.
Definition: PoseRTV.cpp:118
Inverse Depth Factor based on Civera09tro, Montiel06rss.
Definition: Pose3.h:37
Definition: Ordering.h:34
const Ordering & getOrdering() const
Access the current ordering.
Definition: ConcurrentBatchFilter.h:86
const boost::shared_ptr< CALIBRATION > calibration() const
return the calibration object
Definition: ProjectionFactorPPP.h:159
FullIMUFactor(const Vector3 &accel, const Vector3 &gyro, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model)
time between measurements
Definition: FullIMUFactor.h:37
Definition: ProjectionFactorPPPC.h:34
Vector evaluateError(const double &pk, const double &qk, const double &qk1, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
1/h mr^2 (qk1-qk)+mgrh (1-a) sin((1-a)pk + a*pk1) - pk = 0, with optional derivatives
Definition: Pendulum.h:147
bool verboseCheirality() const
return verbosity
Definition: ProjectionFactorPPPC.h:155
PoseRTV transformed_from(const Pose3 &trans, ChartJacobian Dglobal=boost::none, OptionalJacobian< 9, 6 > Dtrans=boost::none) const
Apply transform to this pose, with optional derivatives equivalent to: local = trans....
Definition: PoseRTV.cpp:182
Values calculateEstimate() const
Compute the current best estimate of all variables and return a full Values structure.
Definition: ConcurrentBatchFilter.h:98
VelocityConstraint3()
default constructor to allow for serialization
Definition: VelocityConstraint3.h:20
A Gaussian factor using the canonical parameters (information form)
Definition: HessianFactor.h:101
InvDepthFactorVariant3a()
Default constructor.
Definition: InvDepthFactorVariant3.h:44
PendulumFactorPk()
default constructor to allow for serialization
Definition: Pendulum.h:123
TransformBtwRobotsUnaryFactorEM()
default constructor - only use for serialization
Definition: TransformBtwRobotsUnaryFactorEM.h:78