Skip to content

Commit aba0561

Browse files
authored
Merge pull request #1755 from contagon/python-helpers
Tiny Updates to Python Wrapper
2 parents 50021ed + 32e8a43 commit aba0561

File tree

5 files changed

+33
-1
lines changed

5 files changed

+33
-1
lines changed

gtsam/geometry/geometry.i

+10
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,7 @@ class StereoPoint2 {
6969
// Standard Constructors
7070
StereoPoint2();
7171
StereoPoint2(double uL, double uR, double v);
72+
StereoPoint2(const gtsam::Vector3 &v);
7273

7374
// Testable
7475
void print(string s = "") const;
@@ -836,6 +837,12 @@ class Cal3_S2Stereo {
836837
Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b);
837838
Cal3_S2Stereo(Vector v);
838839

840+
// Manifold
841+
static size_t Dim();
842+
size_t dim() const;
843+
gtsam::Cal3_S2Stereo retract(Vector v) const;
844+
Vector localCoordinates(const gtsam::Cal3_S2Stereo& c) const;
845+
839846
// Testable
840847
void print(string s = "") const;
841848
bool equals(const gtsam::Cal3_S2Stereo& K, double tol) const;
@@ -846,8 +853,11 @@ class Cal3_S2Stereo {
846853
double skew() const;
847854
double px() const;
848855
double py() const;
856+
Matrix K() const;
849857
gtsam::Point2 principalPoint() const;
850858
double baseline() const;
859+
Vector6 vector() const;
860+
Matrix inverse() const;
851861
};
852862

853863
#include <gtsam/geometry/Cal3Bundler.h>

gtsam/navigation/navigation.i

+1-1
Original file line numberDiff line numberDiff line change
@@ -200,7 +200,7 @@ class PreintegratedCombinedMeasurements {
200200
const gtsam::imuBias::ConstantBias& bias) const;
201201
};
202202

203-
virtual class CombinedImuFactor: gtsam::NonlinearFactor {
203+
virtual class CombinedImuFactor: gtsam::NoiseModelFactor {
204204
CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j,
205205
size_t bias_i, size_t bias_j,
206206
const gtsam::PreintegratedCombinedMeasurements& CombinedPreintegratedMeasurements);

gtsam/nonlinear/nonlinear.i

+3
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,7 @@ virtual class NonlinearFactor : gtsam::Factor {
130130
virtual class NoiseModelFactor : gtsam::NonlinearFactor {
131131
bool equals(const gtsam::NoiseModelFactor& other, double tol) const;
132132
gtsam::noiseModel::Base* noiseModel() const;
133+
gtsam::NoiseModelFactor* cloneWithNewNoiseModel(gtsam::noiseModel::Base* newNoise) const;
133134
Vector unwhitenedError(const gtsam::Values& x) const;
134135
Vector whitenedError(const gtsam::Values& x) const;
135136
};
@@ -320,6 +321,8 @@ virtual class GncParams {
320321
enum Verbosity {
321322
SILENT,
322323
SUMMARY,
324+
MU,
325+
WEIGHTS,
323326
VALUES
324327
};
325328
};

gtsam/slam/StereoFactor.h

+5
Original file line numberDiff line numberDiff line change
@@ -169,6 +169,11 @@ class GenericStereoFactor: public NoiseModelFactorN<POSE, LANDMARK> {
169169
/** return flag for throwing cheirality exceptions */
170170
inline bool throwCheirality() const { return throwCheirality_; }
171171

172+
/** return the (optional) sensor pose with respect to the vehicle frame */
173+
const std::optional<POSE>& body_P_sensor() const {
174+
return body_P_sensor_;
175+
}
176+
172177
private:
173178
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
174179
/** Serialization function */

gtsam/slam/slam.i

+14
Original file line numberDiff line numberDiff line change
@@ -171,6 +171,20 @@ virtual class GenericStereoFactor : gtsam::NoiseModelFactor {
171171
GenericStereoFactor(const gtsam::StereoPoint2& measured,
172172
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
173173
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K);
174+
GenericStereoFactor(const gtsam::StereoPoint2& measured,
175+
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
176+
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K,
177+
POSE body_P_sensor);
178+
179+
GenericStereoFactor(const gtsam::StereoPoint2& measured,
180+
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
181+
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K,
182+
bool throwCheirality, bool verboseCheirality);
183+
GenericStereoFactor(const gtsam::StereoPoint2& measured,
184+
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
185+
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K,
186+
bool throwCheirality, bool verboseCheirality,
187+
POSE body_P_sensor);
174188
gtsam::StereoPoint2 measured() const;
175189
gtsam::Cal3_S2Stereo* calibration() const;
176190

0 commit comments

Comments
 (0)