Wrap ManifoldEvaluationFactor for both Rot3 and Pose3
parent
82480fe238
commit
57578a4793
|
|
@ -121,6 +121,13 @@ virtual class ManifoldEvaluationFactor : gtsam::NoiseModelFactor {
|
||||||
double x, double a, double b);
|
double x, double a, double b);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Pose3.h>
|
||||||
|
|
||||||
|
typedef gtsam::ManifoldEvaluationFactor<gtsam::Chebyshev2, gtsam::Rot3>
|
||||||
|
ManifoldEvaluationFactorChebyshev2Rot3;
|
||||||
|
typedef gtsam::ManifoldEvaluationFactor<gtsam::Chebyshev2, gtsam::Pose3>
|
||||||
|
ManifoldEvaluationFactorChebyshev2Pose3;
|
||||||
|
|
||||||
// TODO(gerry): Add `DerivativeFactor`, `VectorDerivativeFactor`, and
|
// TODO(gerry): Add `DerivativeFactor`, `VectorDerivativeFactor`, and
|
||||||
// `ComponentDerivativeFactor`
|
// `ComponentDerivativeFactor`
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue