Merge pull request #738 from borglab/feature/update_print_wrap

release/4.3a0
Varun Agrawal 2021-04-29 16:23:53 -04:00 committed by GitHub
commit 14314071ff
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
3 changed files with 120 additions and 89 deletions

View File

@ -12,6 +12,9 @@ namespace gtsam {
// Actually a FastList<Key>
#include <gtsam/inference/Key.h>
const KeyFormatter DefaultKeyFormatter;
class KeyList {
KeyList();
KeyList(const gtsam::KeyList& other);
@ -47,7 +50,7 @@ class KeySet {
KeySet(const gtsam::KeyList& list);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::KeySet& other) const;
// common STL methods
@ -221,7 +224,7 @@ virtual class Value {
// No constructors because this is an abstract class
// Testable
void print(string s="") const;
void print(string s = "") const;
// Manifold
size_t dim() const;
@ -245,7 +248,7 @@ class Point2 {
Point2(Vector v);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Point2& point, double tol) const;
// Group
@ -298,7 +301,7 @@ class StereoPoint2 {
StereoPoint2(double uL, double uR, double v);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::StereoPoint2& point, double tol) const;
// Group
@ -342,7 +345,7 @@ class Point3 {
Point3(Vector v);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Point3& p, double tol) const;
// Group
@ -379,7 +382,7 @@ class Rot2 {
static gtsam::Rot2 fromCosSin(double c, double s);
// Testable
void print(string s="") const;
void print(string s = "theta") const;
bool equals(const gtsam::Rot2& rot, double tol) const;
// Group
@ -430,7 +433,7 @@ class SO3 {
static gtsam::SO3 ClosestTo(const Matrix M);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::SO3& other, double tol) const;
// Group
@ -460,7 +463,7 @@ class SO4 {
static gtsam::SO4 FromMatrix(Matrix R);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::SO4& other, double tol) const;
// Group
@ -490,7 +493,7 @@ class SOn {
static gtsam::SOn Lift(size_t n, Matrix R);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::SOn& other, double tol) const;
// Group
@ -551,7 +554,7 @@ class Rot3 {
static gtsam::Rot3 ClosestTo(const Matrix M);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Rot3& rot, double tol) const;
// Group
@ -608,7 +611,7 @@ class Pose2 {
Pose2(Vector v);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Pose2& pose, double tol) const;
// Group
@ -668,7 +671,7 @@ class Pose3 {
Pose3(Matrix mat);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Pose3& pose, double tol) const;
// Group
@ -744,7 +747,7 @@ class Unit3 {
Unit3(const gtsam::Point3& pose);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Unit3& pose, double tol) const;
// Other functionality
@ -774,7 +777,7 @@ class EssentialMatrix {
EssentialMatrix(const gtsam::Rot3& aRb, const gtsam::Unit3& aTb);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::EssentialMatrix& pose, double tol) const;
// Manifold
@ -799,7 +802,7 @@ class Cal3_S2 {
Cal3_S2(double fov, int w, int h);
// Testable
void print(string s="") const;
void print(string s = "Cal3_S2") const;
bool equals(const gtsam::Cal3_S2& rhs, double tol) const;
// Manifold
@ -836,7 +839,7 @@ virtual class Cal3DS2_Base {
Cal3DS2_Base();
// Testable
void print(string s="") const;
void print(string s = "") const;
// Standard Interface
double fx() const;
@ -922,7 +925,7 @@ class Cal3_S2Stereo {
Cal3_S2Stereo(Vector v);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Cal3_S2Stereo& K, double tol) const;
// Standard Interface
@ -943,7 +946,7 @@ class Cal3Bundler {
Cal3Bundler(double fx, double k1, double k2, double u0, double v0, double tol);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::Cal3Bundler& rhs, double tol) const;
// Manifold
@ -983,7 +986,7 @@ class CalibratedCamera {
static gtsam::CalibratedCamera Level(const gtsam::Pose2& pose2, double height);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::CalibratedCamera& camera, double tol) const;
// Manifold
@ -1022,7 +1025,7 @@ class PinholeCamera {
const gtsam::Point3& upVector, const CALIBRATION& K);
// Testable
void print(string s="") const;
void print(string s = "PinholeCamera") const;
bool equals(const This& camera, double tol) const;
// Standard Interface
@ -1097,7 +1100,7 @@ class StereoCamera {
StereoCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2Stereo* K);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::StereoCamera& camera, double tol) const;
// Standard Interface
@ -1160,7 +1163,8 @@ virtual class SymbolicFactor {
// From Factor
size_t size() const;
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::SymbolicFactor& other, double tol) const;
gtsam::KeyVector keys();
};
@ -1173,7 +1177,8 @@ virtual class SymbolicFactorGraph {
// From FactorGraph
void push_back(gtsam::SymbolicFactor* factor);
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const;
size_t size() const;
bool exists(size_t idx) const;
@ -1223,7 +1228,8 @@ virtual class SymbolicConditional : gtsam::SymbolicFactor {
static gtsam::SymbolicConditional FromKeys(const gtsam::KeyVector& keys, size_t nrFrontals);
// Testable
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::SymbolicConditional& other, double tol) const;
// Standard interface
@ -1236,7 +1242,8 @@ class SymbolicBayesNet {
SymbolicBayesNet();
SymbolicBayesNet(const gtsam::SymbolicBayesNet& other);
// Testable
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::SymbolicBayesNet& other, double tol) const;
// Standard interface
@ -1257,7 +1264,8 @@ class SymbolicBayesTree {
SymbolicBayesTree(const gtsam::SymbolicBayesTree& other);
// Testable
void print(string s="");
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter);
bool equals(const gtsam::SymbolicBayesTree& other, double tol) const;
//Standard Interface
@ -1279,7 +1287,8 @@ class SymbolicBayesTree {
// SymbolicBayesTreeClique(const pair<typename ConditionalType::shared_ptr, typename ConditionalType::FactorType::shared_ptr>& result) : Base(result) {}
//
// bool equals(const This& other, double tol) const;
// void print(string s="") const;
// void print(string s = "",
// const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const;
// void printTree() const; // Default indent of ""
// void printTree(string indent) const;
// size_t numCachedSeparatorMarginals() const;
@ -1313,7 +1322,9 @@ class VariableIndex {
// Testable
bool equals(const gtsam::VariableIndex& other, double tol) const;
void print(string s="") const;
void print(string s = "VariableIndex: ",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
// Standard interface
size_t size() const;
@ -1328,7 +1339,7 @@ class VariableIndex {
namespace noiseModel {
#include <gtsam/linear/NoiseModel.h>
virtual class Base {
void print(string s="") const;
void print(string s = "") const;
// Methods below are available for all noise models. However, can't add them
// because wrap (incorrectly) thinks robust classes derive from this Base as well.
// bool isConstrained() const;
@ -1411,7 +1422,7 @@ virtual class Unit : gtsam::noiseModel::Isotropic {
namespace mEstimator {
virtual class Base {
void print(string s="") const;
void print(string s = "") const;
};
virtual class Null: gtsam::noiseModel::mEstimator::Base {
@ -1551,7 +1562,9 @@ class VectorValues {
size_t size() const;
size_t dim(size_t j) const;
bool exists(size_t j) const;
void print(string s="") const;
void print(string s = "VectorValues",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::VectorValues& expected, double tol) const;
void insert(size_t j, Vector value);
Vector vector() const;
@ -1582,7 +1595,8 @@ class VectorValues {
#include <gtsam/linear/GaussianFactor.h>
virtual class GaussianFactor {
gtsam::KeyVector keys() const;
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
double error(const gtsam::VectorValues& c) const;
gtsam::GaussianFactor* clone() const;
@ -1610,7 +1624,8 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
JacobianFactor(const gtsam::GaussianFactorGraph& graph);
//Testable
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void printKeys(string s) const;
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
size_t size() const;
@ -1659,7 +1674,8 @@ virtual class HessianFactor : gtsam::GaussianFactor {
//Testable
size_t size() const;
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void printKeys(string s) const;
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
double error(const gtsam::VectorValues& c) const;
@ -1684,7 +1700,8 @@ class GaussianFactorGraph {
GaussianFactorGraph(const gtsam::GaussianBayesTree& bayesTree);
// From FactorGraph
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const;
size_t size() const;
gtsam::GaussianFactor* at(size_t idx) const;
@ -1775,20 +1792,23 @@ virtual class GaussianConditional : gtsam::JacobianFactor {
size_t name2, Matrix T);
//Standard Interface
void print(string s="") const;
bool equals(const gtsam::GaussianConditional &cg, double tol) const;
void print(string s = "GaussianConditional",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::GaussianConditional& cg, double tol) const;
//Advanced Interface
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents, const gtsam::VectorValues& rhs) const;
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
void scaleFrontalsBySigma(gtsam::VectorValues& gy) const;
Matrix R() const;
Matrix S() const;
Vector d() const;
// Advanced Interface
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
const gtsam::VectorValues& rhs) const;
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
void scaleFrontalsBySigma(gtsam::VectorValues& gy) const;
Matrix R() const;
Matrix S() const;
Vector d() const;
// enabling serialization functionality
void serialize() const;
// enabling serialization functionality
void serialize() const;
};
#include <gtsam/linear/GaussianDensity.h>
@ -1797,7 +1817,9 @@ virtual class GaussianDensity : gtsam::GaussianConditional {
GaussianDensity(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas);
//Standard Interface
void print(string s="") const;
void print(string s = "GaussianDensity",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::GaussianDensity &cg, double tol) const;
Vector mean() const;
Matrix covariance() const;
@ -1810,7 +1832,8 @@ virtual class GaussianBayesNet {
GaussianBayesNet(const gtsam::GaussianConditional* conditional);
// Testable
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::GaussianBayesNet& other, double tol) const;
size_t size() const;
@ -1845,7 +1868,8 @@ virtual class GaussianBayesTree {
GaussianBayesTree();
GaussianBayesTree(const gtsam::GaussianBayesTree& other);
bool equals(const gtsam::GaussianBayesTree& other, double tol) const;
void print(string s="");
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter);
size_t size() const;
bool empty() const;
size_t numCachedSeparatorMarginals() const;
@ -1871,7 +1895,7 @@ class Errors {
Errors(const gtsam::VectorValues& V);
//Testable
void print(string s="");
void print(string s = "Errors");
bool equals(const gtsam::Errors& expected, double tol) const;
};
@ -1890,7 +1914,6 @@ class GaussianISAM {
virtual class IterativeOptimizationParameters {
string getVerbosity() const;
void setVerbosity(string s) ;
void print() const;
};
//virtual class IterativeSolver {
@ -1912,7 +1935,6 @@ virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParamete
void setReset(int value);
void setEpsilon_rel(double value);
void setEpsilon_abs(double value);
void print() const;
};
#include <gtsam/linear/Preconditioner.h>
@ -1927,14 +1949,13 @@ virtual class DummyPreconditionerParameters : gtsam::PreconditionerParameters {
#include <gtsam/linear/PCGSolver.h>
virtual class PCGSolverParameters : gtsam::ConjugateGradientParameters {
PCGSolverParameters();
void print(string s="");
void print(string s = "");
void setPreconditionerParams(gtsam::PreconditionerParameters* preconditioner);
};
#include <gtsam/linear/SubgraphSolver.h>
virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters {
SubgraphSolverParameters();
void print() const;
};
virtual class SubgraphSolver {
@ -1948,7 +1969,7 @@ class KalmanFilter {
KalmanFilter(size_t n);
// gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0);
gtsam::GaussianDensity* init(Vector x0, Matrix P0);
void print(string s="") const;
void print(string s = "") const;
static size_t step(gtsam::GaussianDensity* p);
gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F,
Matrix B, Vector u, const gtsam::noiseModel::Diagonal* modelQ);
@ -1974,7 +1995,7 @@ class Symbol {
Symbol(size_t key);
size_t key() const;
void print(const string& s) const;
void print(const string& s = "") const;
bool equals(const gtsam::Symbol& expected, double tol) const;
char chr() const;
@ -2039,7 +2060,7 @@ class LabeledSymbol {
gtsam::LabeledSymbol newChr(unsigned char c) const;
gtsam::LabeledSymbol newLabel(unsigned char label) const;
void print(string s="") const;
void print(string s = "") const;
};
size_t mrsymbol(unsigned char c, unsigned char label, size_t j);
@ -2054,7 +2075,8 @@ class Ordering {
Ordering(const gtsam::Ordering& other);
// Testable
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::Ordering& ord, double tol) const;
// Standard interface
@ -2075,7 +2097,8 @@ class NonlinearFactorGraph {
NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);
// FactorGraph
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const;
size_t size() const;
bool empty() const;
@ -2123,7 +2146,8 @@ virtual class NonlinearFactor {
// Factor base class
size_t size() const;
gtsam::KeyVector keys() const;
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void printKeys(string s) const;
// NonlinearFactor
bool equals(const gtsam::NonlinearFactor& other, double tol) const;
@ -2153,7 +2177,8 @@ class Values {
void clear();
size_t dim() const;
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::Values& other, double tol) const;
void insert(const gtsam::Values& values);
@ -2242,7 +2267,8 @@ class Marginals {
Marginals(const gtsam::GaussianFactorGraph& gfgraph,
const gtsam::VectorValues& solutionvec);
void print(string s="") const;
void print(string s = "Marginals: ", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
Matrix marginalCovariance(size_t variable) const;
Matrix marginalInformation(size_t variable) const;
gtsam::JointMarginal jointMarginalCovariance(const gtsam::KeyVector& variables) const;
@ -2252,8 +2278,7 @@ class Marginals {
class JointMarginal {
Matrix at(size_t iVariable, size_t jVariable) const;
Matrix fullMatrix() const;
void print(string s="") const;
void print() const;
void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter) const;
};
#include <gtsam/nonlinear/LinearContainerFactor.h>
@ -2296,7 +2321,7 @@ virtual class LinearContainerFactor : gtsam::NonlinearFactor {
#include <gtsam/nonlinear/NonlinearOptimizerParams.h>
virtual class NonlinearOptimizerParams {
NonlinearOptimizerParams();
void print(string s="") const;
void print(string s = "") const;
int getMaxIterations() const;
double getRelativeErrorTol() const;
@ -2407,14 +2432,14 @@ virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer {
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues);
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::LevenbergMarquardtParams& params);
double lambda() const;
void print(string str) const;
void print(string s = "") const;
};
#include <gtsam/nonlinear/ISAM2.h>
class ISAM2GaussNewtonParams {
ISAM2GaussNewtonParams();
void print(string str) const;
void print(string s = "") const;
/** Getters and Setters for all properties */
double getWildfireThreshold() const;
@ -2424,7 +2449,7 @@ class ISAM2GaussNewtonParams {
class ISAM2DoglegParams {
ISAM2DoglegParams();
void print(string str) const;
void print(string s = "") const;
/** Getters and Setters for all properties */
double getWildfireThreshold() const;
@ -2460,7 +2485,7 @@ class ISAM2ThresholdMap {
class ISAM2Params {
ISAM2Params();
void print(string str) const;
void print(string s = "") const;
/** Getters and Setters for all properties */
void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& gauss_newton__params);
@ -2490,13 +2515,13 @@ class ISAM2Clique {
//Standard Interface
Vector gradientContribution() const;
void print(string s="");
void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter);
};
class ISAM2Result {
ISAM2Result();
void print(string str) const;
void print(string s = "") const;
/** Getters and Setters for all properties */
size_t getVariablesRelinearized() const;
@ -2512,7 +2537,8 @@ class ISAM2 {
ISAM2(const gtsam::ISAM2& other);
bool equals(const gtsam::ISAM2& other, double tol) const;
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void printStats() const;
void saveGraph(string s) const;
@ -2544,7 +2570,8 @@ class ISAM2 {
class NonlinearISAM {
NonlinearISAM();
NonlinearISAM(int reorderInterval);
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void printStats() const;
void saveGraph(string s) const;
gtsam::Values estimate() const;
@ -2679,7 +2706,7 @@ class BearingRange {
static This Measure(const POSE& pose, const POINT& point);
static BEARING MeasureBearing(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;
};
typedef gtsam::BearingRange<gtsam::Pose2, gtsam::Point2, gtsam::Rot2, double> BearingRange2D;
@ -3016,7 +3043,6 @@ class ShonanAveragingParameters2 {
bool getUseHuber() const;
void setCertifyOptimality(bool value);
bool getCertifyOptimality() const;
void print() const;
};
class ShonanAveragingParameters3 {
@ -3037,7 +3063,6 @@ class ShonanAveragingParameters3 {
bool getUseHuber() const;
void setCertifyOptimality(bool value);
bool getCertifyOptimality() const;
void print() const;
};
class ShonanAveraging2 {
@ -3167,7 +3192,7 @@ class ConstantBias {
ConstantBias(Vector biasAcc, Vector biasGyro);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::imuBias::ConstantBias& expected, double tol) const;
// Group
@ -3207,7 +3232,7 @@ class NavState {
NavState(const gtsam::Pose3& pose, Vector v);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::NavState& expected, double tol) const;
// Access
@ -3225,7 +3250,7 @@ virtual class PreintegratedRotationParams {
PreintegratedRotationParams();
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::PreintegratedRotationParams& expected, double tol);
void setGyroscopeCovariance(Matrix cov);
@ -3248,7 +3273,7 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams {
static gtsam::PreintegrationParams* MakeSharedU(); // default g = 9.81
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::PreintegrationParams& expected, double tol);
void setAccelerometerCovariance(Matrix cov);
@ -3268,7 +3293,7 @@ class PreintegratedImuMeasurements {
const gtsam::imuBias::ConstantBias& bias);
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::PreintegratedImuMeasurements& expected, double tol);
// Standard Interface
@ -3311,7 +3336,7 @@ virtual class PreintegrationCombinedParams : gtsam::PreintegrationParams {
static gtsam::PreintegrationCombinedParams* MakeSharedU(); // default g = 9.81
// Testable
void print(string s="") const;
void print(string s = "") const;
bool equals(const gtsam::PreintegrationCombinedParams& expected, double tol);
void setBiasAccCovariance(Matrix cov);
@ -3330,7 +3355,7 @@ class PreintegratedCombinedMeasurements {
PreintegratedCombinedMeasurements(const gtsam::PreintegrationCombinedParams* params,
const gtsam::imuBias::ConstantBias& bias);
// Testable
void print(string s="") const;
void print(string s = "Preintegrated Measurements:") const;
bool equals(const gtsam::PreintegratedCombinedMeasurements& expected,
double tol);
@ -3371,7 +3396,7 @@ class PreintegratedAhrsMeasurements {
PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs);
// Testable
void print(string s="") const;
void print(string s = "Preintegrated Measurements: ") const;
bool equals(const gtsam::PreintegratedAhrsMeasurements& expected, double tol);
// get Data
@ -3410,7 +3435,8 @@ virtual class Rot3AttitudeFactor : gtsam::NonlinearFactor{
const gtsam::Unit3& bRef);
Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model);
Rot3AttitudeFactor();
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
gtsam::Unit3 nZ() const;
gtsam::Unit3 bRef() const;
@ -3423,7 +3449,8 @@ virtual class Pose3AttitudeFactor : gtsam::NonlinearFactor {
Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ,
const gtsam::noiseModel::Diagonal* model);
Pose3AttitudeFactor();
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
gtsam::Unit3 nZ() const;
gtsam::Unit3 bRef() const;
@ -3435,7 +3462,8 @@ virtual class GPSFactor : gtsam::NonlinearFactor{
const gtsam::noiseModel::Base* model);
// Testable
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::GPSFactor& expected, double tol);
// Standard Interface
@ -3447,7 +3475,8 @@ virtual class GPSFactor2 : gtsam::NonlinearFactor {
const gtsam::noiseModel::Base* model);
// Testable
void print(string s="") const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::GPSFactor2& expected, double tol);
// Standard Interface

View File

@ -13,6 +13,7 @@
#include <pybind11/eigen.h>
#include <pybind11/stl_bind.h>
#include <pybind11/pybind11.h>
#include <pybind11/functional.h>
#include <pybind11/iostream.h>
#include "gtsam/config.h"
#include "gtsam/base/serialization.h"

View File

@ -13,6 +13,7 @@
#include <pybind11/eigen.h>
#include <pybind11/stl_bind.h>
#include <pybind11/pybind11.h>
#include <pybind11/functional.h>
#include <pybind11/iostream.h>
#include "gtsam/base/serialization.h"
#include "gtsam/nonlinear/utilities.h" // for RedirectCout.