Wrapped measured() for BearingRangeFactor.
parent
b82524882c
commit
2b20d61221
2
gtsam.h
2
gtsam.h
|
@ -2140,6 +2140,8 @@ template<POSE, POINT, ROTATION>
|
|||
virtual class BearingRangeFactor : gtsam::NoiseModelFactor {
|
||||
BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel);
|
||||
|
||||
pair<ROTATION, double> measured() const;
|
||||
|
||||
// enabling serialization functionality
|
||||
void serialize() const;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue