ISAM2: wrap full update method and error method
parent
7703b7dca2
commit
d3bcfddfb5
|
@ -507,18 +507,18 @@ class ISAM2 {
|
||||||
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors,
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors,
|
||||||
const gtsam::Values& newTheta,
|
const gtsam::Values& newTheta,
|
||||||
const gtsam::FactorIndices& removeFactorIndices,
|
const gtsam::FactorIndices& removeFactorIndices,
|
||||||
gtsam::KeyGroupMap& constrainedKeys,
|
const gtsam::KeyGroupMap& constrainedKeys,
|
||||||
const gtsam::KeyList& noRelinKeys);
|
const gtsam::KeyList& noRelinKeys);
|
||||||
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors,
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors,
|
||||||
const gtsam::Values& newTheta,
|
const gtsam::Values& newTheta,
|
||||||
const gtsam::FactorIndices& removeFactorIndices,
|
const gtsam::FactorIndices& removeFactorIndices,
|
||||||
gtsam::KeyGroupMap& constrainedKeys,
|
const gtsam::KeyGroupMap& constrainedKeys,
|
||||||
const gtsam::KeyList& noRelinKeys,
|
const gtsam::KeyList& noRelinKeys,
|
||||||
const gtsam::KeyList& extraReelimKeys);
|
const gtsam::KeyList& extraReelimKeys);
|
||||||
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors,
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors,
|
||||||
const gtsam::Values& newTheta,
|
const gtsam::Values& newTheta,
|
||||||
const gtsam::FactorIndices& removeFactorIndices,
|
const gtsam::FactorIndices& removeFactorIndices,
|
||||||
gtsam::KeyGroupMap& constrainedKeys,
|
const gtsam::KeyGroupMap& constrainedKeys,
|
||||||
const gtsam::KeyList& noRelinKeys,
|
const gtsam::KeyList& noRelinKeys,
|
||||||
const gtsam::KeyList& extraReelimKeys,
|
const gtsam::KeyList& extraReelimKeys,
|
||||||
bool force_relinearize);
|
bool force_relinearize);
|
||||||
|
@ -527,6 +527,8 @@ class ISAM2 {
|
||||||
const gtsam::Values& newTheta,
|
const gtsam::Values& newTheta,
|
||||||
const gtsam::ISAM2UpdateParams& updateParams);
|
const gtsam::ISAM2UpdateParams& updateParams);
|
||||||
|
|
||||||
|
double error(const gtsam::VectorValues& values) const;
|
||||||
|
|
||||||
gtsam::Values getLinearizationPoint() const;
|
gtsam::Values getLinearizationPoint() const;
|
||||||
bool valueExists(gtsam::Key key) const;
|
bool valueExists(gtsam::Key key) const;
|
||||||
gtsam::Values calculateEstimate() const;
|
gtsam::Values calculateEstimate() const;
|
||||||
|
|
Loading…
Reference in New Issue