add missing default arg on useOdometricPath
parent
bc68ecb5ab
commit
97fee355ee
|
|
@ -337,8 +337,8 @@ virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor {
|
||||||
|
|
||||||
#include <gtsam/slam/lago.h>
|
#include <gtsam/slam/lago.h>
|
||||||
namespace lago {
|
namespace lago {
|
||||||
|
gtsam::Values initialize(const gtsam::NonlinearFactorGraph& graph, bool useOdometricPath = true);
|
||||||
gtsam::Values initialize(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialGuess);
|
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