wrap BearingRange classes and factors
parent
b91c43e691
commit
f5ec070f9f
|
@ -1279,5 +1279,11 @@ class BearingRange {
|
||||||
|
|
||||||
typedef gtsam::BearingRange<gtsam::Pose2, gtsam::Point2, gtsam::Rot2, double>
|
typedef gtsam::BearingRange<gtsam::Pose2, gtsam::Point2, gtsam::Rot2, double>
|
||||||
BearingRange2D;
|
BearingRange2D;
|
||||||
|
typedef gtsam::BearingRange<gtsam::Pose2, gtsam::Pose2, gtsam::Rot2, double>
|
||||||
|
BearingRangePose2;
|
||||||
|
typedef gtsam::BearingRange<gtsam::Pose3, gtsam::Point3, gtsam::Unit3, double>
|
||||||
|
BearingRange3D;
|
||||||
|
typedef gtsam::BearingRange<gtsam::Pose3, gtsam::Pose3, gtsam::Unit3, double>
|
||||||
|
BearingRangePose3;
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -108,5 +108,11 @@ typedef gtsam::BearingRangeFactor<gtsam::Pose2, gtsam::Point2, gtsam::Rot2,
|
||||||
typedef gtsam::BearingRangeFactor<gtsam::Pose2, gtsam::Pose2, gtsam::Rot2,
|
typedef gtsam::BearingRangeFactor<gtsam::Pose2, gtsam::Pose2, gtsam::Rot2,
|
||||||
double>
|
double>
|
||||||
BearingRangeFactorPose2;
|
BearingRangeFactorPose2;
|
||||||
|
typedef gtsam::BearingRangeFactor<gtsam::Pose3, gtsam::Point3, gtsam::Unit3,
|
||||||
|
double>
|
||||||
|
BearingRangeFactor3D;
|
||||||
|
typedef gtsam::BearingRangeFactor<gtsam::Pose3, gtsam::Pose3, gtsam::Unit3,
|
||||||
|
double>
|
||||||
|
BearingRangeFactorPose3;
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
Loading…
Reference in New Issue