Expanded stereofactor python constructor

release/4.3a0
Easton Potokar 2024-05-27 15:58:05 -04:00
parent e116123ea5
commit d7e2e1cdf6
2 changed files with 18 additions and 0 deletions

View File

@ -169,6 +169,11 @@ public:
/** return flag for throwing cheirality exceptions */
inline bool throwCheirality() const { return throwCheirality_; }
/** return the (optional) sensor pose with respect to the vehicle frame */
const std::optional<POSE>& body_P_sensor() const {
return body_P_sensor_;
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */

View File

@ -168,10 +168,23 @@ typedef gtsam::SmartProjectionPoseFactor<gtsam::Cal3_S2>
#include <gtsam/slam/StereoFactor.h>
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);
GenericStereoFactor(const gtsam::StereoPoint2& measured,
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K,
POSE body_P_sensor);
GenericStereoFactor(const gtsam::StereoPoint2& measured,
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K,
bool throwCheirality, bool verboseCheirality);
GenericStereoFactor(const gtsam::StereoPoint2& measured,
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
size_t landmarkKey, const gtsam::Cal3_S2Stereo* K,
bool throwCheirality, bool verboseCheirality,
POSE body_P_sensor);
gtsam::StereoPoint2 measured() const;
gtsam::Cal3_S2Stereo* calibration() const;