Remove deprecated methods from wrapper
parent
906176291f
commit
a25e3f6d38
|
@ -128,7 +128,7 @@ namespace gtsam {
|
||||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
|
||||||
/** Scale the values in \c gy according to the sigmas for the frontal variables in this
|
/** Scale the values in \c gy according to the sigmas for the frontal variables in this
|
||||||
* conditional. */
|
* conditional. */
|
||||||
void scaleFrontalsBySigma(VectorValues& gy) const;
|
void GTSAM_DEPRECATED scaleFrontalsBySigma(VectorValues& gy) const;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -467,7 +467,6 @@ virtual class GaussianConditional : gtsam::JacobianFactor {
|
||||||
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
|
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
|
||||||
const gtsam::VectorValues& rhs) const;
|
const gtsam::VectorValues& rhs) const;
|
||||||
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
||||||
void scaleFrontalsBySigma(gtsam::VectorValues& gy) const;
|
|
||||||
Matrix R() const;
|
Matrix R() const;
|
||||||
Matrix S() const;
|
Matrix S() const;
|
||||||
Vector d() const;
|
Vector d() const;
|
||||||
|
|
|
@ -18,23 +18,12 @@ class ConstantBias {
|
||||||
|
|
||||||
// Group
|
// Group
|
||||||
static gtsam::imuBias::ConstantBias identity();
|
static gtsam::imuBias::ConstantBias identity();
|
||||||
gtsam::imuBias::ConstantBias inverse() const;
|
|
||||||
gtsam::imuBias::ConstantBias compose(const gtsam::imuBias::ConstantBias& b) const;
|
|
||||||
gtsam::imuBias::ConstantBias between(const gtsam::imuBias::ConstantBias& b) const;
|
|
||||||
|
|
||||||
// Operator Overloads
|
// Operator Overloads
|
||||||
gtsam::imuBias::ConstantBias operator-() const;
|
gtsam::imuBias::ConstantBias operator-() const;
|
||||||
gtsam::imuBias::ConstantBias operator+(const gtsam::imuBias::ConstantBias& b) const;
|
gtsam::imuBias::ConstantBias operator+(const gtsam::imuBias::ConstantBias& b) const;
|
||||||
gtsam::imuBias::ConstantBias operator-(const gtsam::imuBias::ConstantBias& b) const;
|
gtsam::imuBias::ConstantBias operator-(const gtsam::imuBias::ConstantBias& b) const;
|
||||||
|
|
||||||
// Manifold
|
|
||||||
gtsam::imuBias::ConstantBias retract(Vector v) const;
|
|
||||||
Vector localCoordinates(const gtsam::imuBias::ConstantBias& b) const;
|
|
||||||
|
|
||||||
// Lie Group
|
|
||||||
static gtsam::imuBias::ConstantBias Expmap(Vector v);
|
|
||||||
static Vector Logmap(const gtsam::imuBias::ConstantBias& b);
|
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
Vector vector() const;
|
Vector vector() const;
|
||||||
Vector accelerometer() const;
|
Vector accelerometer() const;
|
||||||
|
|
|
@ -264,8 +264,6 @@ pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
||||||
string filename, gtsam::noiseModel::Diagonal* model);
|
string filename, gtsam::noiseModel::Diagonal* model);
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(string filename);
|
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(string filename);
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D_robust(
|
|
||||||
string filename, gtsam::noiseModel::Base* model, int maxIndex);
|
|
||||||
void save2D(const gtsam::NonlinearFactorGraph& graph,
|
void save2D(const gtsam::NonlinearFactorGraph& graph,
|
||||||
const gtsam::Values& config, gtsam::noiseModel::Diagonal* model,
|
const gtsam::Values& config, gtsam::noiseModel::Diagonal* model,
|
||||||
string filename);
|
string filename);
|
||||||
|
|
Loading…
Reference in New Issue