Add a few functions to python wrapper

release/4.3a0
Easton Potokar 2024-05-27 13:31:43 -04:00
parent 42b27e4484
commit e116123ea5
4 changed files with 16 additions and 2 deletions

View File

@ -69,6 +69,7 @@ class StereoPoint2 {
// Standard Constructors
StereoPoint2();
StereoPoint2(double uL, double uR, double v);
StereoPoint2(const gtsam::Vector3 &v);
// Testable
void print(string s = "") const;
@ -836,6 +837,12 @@ class Cal3_S2Stereo {
Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b);
Cal3_S2Stereo(Vector v);
// Manifold
static size_t Dim();
size_t dim() const;
gtsam::Cal3_S2Stereo retract(Vector v) const;
Vector localCoordinates(const gtsam::Cal3_S2Stereo& c) const;
// Testable
void print(string s = "") const;
bool equals(const gtsam::Cal3_S2Stereo& K, double tol) const;
@ -846,8 +853,11 @@ class Cal3_S2Stereo {
double skew() const;
double px() const;
double py() const;
Matrix K() const;
gtsam::Point2 principalPoint() const;
double baseline() const;
Vector6 vector() const;
Matrix inverse() const;
};
#include <gtsam/geometry/Cal3Bundler.h>

View File

@ -200,7 +200,7 @@ class PreintegratedCombinedMeasurements {
const gtsam::imuBias::ConstantBias& bias) const;
};
virtual class CombinedImuFactor: gtsam::NonlinearFactor {
virtual class CombinedImuFactor: gtsam::NoiseModelFactor {
CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j,
size_t bias_i, size_t bias_j,
const gtsam::PreintegratedCombinedMeasurements& CombinedPreintegratedMeasurements);

View File

@ -130,6 +130,7 @@ virtual class NonlinearFactor : gtsam::Factor {
virtual class NoiseModelFactor : gtsam::NonlinearFactor {
bool equals(const gtsam::NoiseModelFactor& other, double tol) const;
gtsam::noiseModel::Base* noiseModel() const;
gtsam::NoiseModelFactor* cloneWithNewNoiseModel(gtsam::noiseModel::Base* newNoise) const;
Vector unwhitenedError(const gtsam::Values& x) const;
Vector whitenedError(const gtsam::Values& x) const;
};
@ -320,6 +321,8 @@ virtual class GncParams {
enum Verbosity {
SILENT,
SUMMARY,
MU,
WEIGHTS,
VALUES
};
};

View File

@ -170,7 +170,8 @@ template <POSE, LANDMARK>
virtual class GenericStereoFactor : gtsam::NoiseModelFactor {
GenericStereoFactor(const gtsam::StereoPoint2& measured,
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K);
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K,
POSE body_P_sensor);
gtsam::StereoPoint2 measured() const;
gtsam::Cal3_S2Stereo* calibration() const;