Merge pull request #646 from cttdev/bearing-factor-3d
Adding BearingFactor3D to the wrapper definition.release/4.3a0
						commit
						2597a7cf1f
					
				|  | @ -2599,6 +2599,7 @@ virtual class BearingFactor : gtsam::NoiseModelFactor { | |||
| }; | ||||
| 
 | ||||
| typedef gtsam::BearingFactor<gtsam::Pose2, gtsam::Point2, gtsam::Rot2> BearingFactor2D; | ||||
| typedef gtsam::BearingFactor<gtsam::Pose3, gtsam::Point3, gtsam::Unit3> BearingFactor3D; | ||||
| typedef gtsam::BearingFactor<gtsam::Pose2, gtsam::Pose2, gtsam::Rot2> BearingFactorPose2; | ||||
| 
 | ||||
| #include <gtsam/geometry/BearingRange.h> | ||||
|  |  | |||
|  | @ -99,6 +99,7 @@ | |||
| %  | ||||
| %% SLAM and SFM | ||||
| %   BearingFactor2D                   - class BearingFactor2D, see Doxygen page for details | ||||
| %   BearingFactor3D                   - class BearingFactor3D, see Doxygen page for details | ||||
| %   BearingRangeFactor2D              - class BearingRangeFactor2D, see Doxygen page for details | ||||
| %   BetweenFactorLieMatrix            - class BetweenFactorLieMatrix, see Doxygen page for details | ||||
| %   BetweenFactorLieScalar            - class BetweenFactorLieScalar, see Doxygen page for details | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue