fix wrapper TODOs for ISAM2 and BearingRange
parent
0043120a8a
commit
f9749c8aff
|
|
@ -314,6 +314,14 @@ class DSFMapIndexPair {
|
||||||
gtsam::IndexPairSetMap sets();
|
gtsam::IndexPairSetMap sets();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/base/FastList.h>
|
||||||
|
template<VALUE>
|
||||||
|
class FastList {};
|
||||||
|
|
||||||
|
#include <gtsam/base/FastMap.h>
|
||||||
|
template<KEY, VALUE>
|
||||||
|
class FastMap {};
|
||||||
|
|
||||||
#include <gtsam/base/Matrix.h>
|
#include <gtsam/base/Matrix.h>
|
||||||
bool linear_independent(Matrix A, Matrix B, double tol);
|
bool linear_independent(Matrix A, Matrix B, double tol);
|
||||||
|
|
||||||
|
|
@ -2567,9 +2575,10 @@ class ISAM2 {
|
||||||
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
|
||||||
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices);
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices);
|
||||||
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, const gtsam::KeyGroupMap& constrainedKeys);
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FactorIndices& removeFactorIndices, const gtsam::KeyGroupMap& constrainedKeys);
|
||||||
// TODO: wrap the full version of update
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap<gtsam::Key,int>& constrainedKeys);
|
||||||
//void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap<Key,int>& constrainedKeys);
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap<gtsam::Key,int>& constrainedKeys, const gtsam::FastList<gtsam::Key>& noRelinKeys);
|
||||||
//void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap<Key,int>& constrainedKeys, bool force_relinearize);
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap<gtsam::Key,int>& constrainedKeys, const gtsam::FastList<gtsam::Key>& noRelinKeys, const gtsam::FastList<gtsam::Key>& extraReelimKeys);
|
||||||
|
gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, gtsam::FastMap<gtsam::Key,int>& constrainedKeys, const gtsam::FastList<gtsam::Key>& noRelinKeys, const gtsam::FastList<gtsam::Key>& extraReelimKeys, bool force_relinearize);
|
||||||
|
|
||||||
gtsam::Values getLinearizationPoint() const;
|
gtsam::Values getLinearizationPoint() const;
|
||||||
gtsam::Values calculateEstimate() const;
|
gtsam::Values calculateEstimate() const;
|
||||||
|
|
@ -2701,8 +2710,7 @@ class BearingRange {
|
||||||
BearingRange(const BEARING& b, const RANGE& r);
|
BearingRange(const BEARING& b, const RANGE& r);
|
||||||
BEARING bearing() const;
|
BEARING bearing() const;
|
||||||
RANGE range() const;
|
RANGE range() const;
|
||||||
// TODO(frank): can't class instance itself?
|
static gtsam::BearingRange Measure(const POSE& pose, const POINT& point);
|
||||||
// static gtsam::BearingRange Measure(const POSE& pose, const POINT& point);
|
|
||||||
static BEARING MeasureBearing(const POSE& pose, const POINT& point);
|
static BEARING MeasureBearing(const POSE& pose, const POINT& point);
|
||||||
static RANGE MeasureRange(const POSE& pose, const POINT& point);
|
static RANGE MeasureRange(const POSE& pose, const POINT& point);
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue