@@ -171,6 +171,20 @@ virtual class GenericStereoFactor : gtsam::NoiseModelFactor {
171
171
GenericStereoFactor (const gtsam::StereoPoint2& measured,
172
172
const gtsam::noiseModel::Base* noiseModel, size_t poseKey,
173
173
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);
174
188
gtsam::StereoPoint2 measured () const ;
175
189
gtsam::Cal3_S2Stereo* calibration () const ;
176
190
0 commit comments