add LAGO (for Pose2) to python wrapper
parent
0a6a6b00b8
commit
4dbd006d7d
|
|
@ -335,4 +335,8 @@ virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor {
|
||||||
Vector evaluateError(const T& R1, const T& R2);
|
Vector evaluateError(const T& R1, const T& R2);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/slam/lago.h>
|
||||||
|
gtsam::Values initialize(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialGuess);
|
||||||
|
gtsam::Values initialize(const gtsam::NonlinearFactorGraph& graph, bool useOdometricPath);
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue