Renamed TransformCalProjectionFactor to ProjectionFactorPPPC to follow new naming convention
							parent
							
								
									bc982293ab
								
							
						
					
					
						commit
						2c3f6e563d
					
				|  | @ -767,13 +767,13 @@ typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal | ||||||
| typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> TransformProjectionFactorCal3DS2; | typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> TransformProjectionFactorCal3DS2; | ||||||
| 
 | 
 | ||||||
| 
 | 
 | ||||||
| #include <gtsam_unstable/slam/TransformCalProjectionFactor.h> | #include <gtsam_unstable/slam/ProjectionFactorPPPC.h> | ||||||
| template<POSE, LANDMARK, CALIBRATION> | template<POSE, LANDMARK, CALIBRATION> | ||||||
| virtual class TransformCalProjectionFactor : gtsam::NoiseModelFactor { | virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor { | ||||||
|   TransformCalProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, |   ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, | ||||||
|     size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey); |     size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey); | ||||||
| 
 | 
 | ||||||
|   TransformCalProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, |   ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, | ||||||
|       size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey, bool throwCheirality, bool verboseCheirality); |       size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey, bool throwCheirality, bool verboseCheirality); | ||||||
| 
 | 
 | ||||||
|   gtsam::Point2 measured() const; |   gtsam::Point2 measured() const; | ||||||
|  | @ -783,7 +783,7 @@ virtual class TransformCalProjectionFactor : gtsam::NoiseModelFactor { | ||||||
|   // enabling serialization functionality
 |   // enabling serialization functionality
 | ||||||
|   void serialize() const; |   void serialize() const; | ||||||
| }; | }; | ||||||
| typedef gtsam::TransformCalProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> TransformCalProjectionFactorCal3_S2; | typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCCal3_S2; | ||||||
| typedef gtsam::TransformCalProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> TransformCalProjectionFactorCal3DS2; | typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCCal3DS2; | ||||||
| 
 | 
 | ||||||
| } //\namespace gtsam
 | } //\namespace gtsam
 | ||||||
|  |  | ||||||
|  | @ -10,32 +10,30 @@ | ||||||
|  * -------------------------------------------------------------------------- */ |  * -------------------------------------------------------------------------- */ | ||||||
| 
 | 
 | ||||||
| /**
 | /**
 | ||||||
|  * @file TransformCalProjectionFactor.h |  * @file ProjectionFactorPPPC.h | ||||||
|  * @brief Basic bearing factor from 2D measurement |  * @brief Derived from ProjectionFactor, but estimates body-camera transform | ||||||
|  |  * and calibration in addition to body pose and 3D landmark | ||||||
|  * @author Chris Beall |  * @author Chris Beall | ||||||
|  * @author Richard Roberts |  | ||||||
|  * @author Frank Dellaert |  | ||||||
|  * @author Alex Cunningham |  | ||||||
|  */ |  */ | ||||||
| 
 | 
 | ||||||
| #pragma once | #pragma once | ||||||
| 
 | 
 | ||||||
| #include <gtsam/nonlinear/NonlinearFactor.h> | #include <gtsam/nonlinear/NonlinearFactor.h> | ||||||
| #include <gtsam/geometry/SimpleCamera.h> | #include <gtsam/geometry/PinholeCamera.h> | ||||||
|  | #include <gtsam/geometry/Cal3_S2.h> | ||||||
| #include <boost/optional.hpp> | #include <boost/optional.hpp> | ||||||
| 
 | 
 | ||||||
| namespace gtsam { | namespace gtsam { | ||||||
| 
 | 
 | ||||||
|   /**
 |   /**
 | ||||||
|    * Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here. |    * Non-linear factor for a constraint derived from a 2D measurement. This factor | ||||||
|    * i.e. the main building block for visual SLAM. |    * estimates the body pose, body-camera transform, 3D landmark, and calibration. | ||||||
|    * @addtogroup SLAM |    * @addtogroup SLAM | ||||||
|    */ |    */ | ||||||
|   template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2> |   template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2> | ||||||
|   class TransformCalProjectionFactor: public NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> { |   class ProjectionFactorPPPC: public NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> { | ||||||
|   protected: |   protected: | ||||||
| 
 | 
 | ||||||
|     // Keep a copy of measurement and calibration for I/O
 |  | ||||||
|     Point2 measured_;                    ///< 2D measurement
 |     Point2 measured_;                    ///< 2D measurement
 | ||||||
| 
 | 
 | ||||||
|     // verbosity handling for Cheirality Exceptions
 |     // verbosity handling for Cheirality Exceptions
 | ||||||
|  | @ -48,13 +46,13 @@ namespace gtsam { | ||||||
|     typedef NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> Base; |     typedef NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> Base; | ||||||
| 
 | 
 | ||||||
|     /// shorthand for this class
 |     /// shorthand for this class
 | ||||||
|     typedef TransformCalProjectionFactor<POSE, LANDMARK, CALIBRATION> This; |     typedef ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> This; | ||||||
| 
 | 
 | ||||||
|     /// shorthand for a smart pointer to a factor
 |     /// shorthand for a smart pointer to a factor
 | ||||||
|     typedef boost::shared_ptr<This> shared_ptr; |     typedef boost::shared_ptr<This> shared_ptr; | ||||||
| 
 | 
 | ||||||
|     /// Default constructor
 |     /// Default constructor
 | ||||||
|     TransformCalProjectionFactor() : throwCheirality_(false), verboseCheirality_(false) {} |     ProjectionFactorPPPC() : throwCheirality_(false), verboseCheirality_(false) {} | ||||||
| 
 | 
 | ||||||
|     /**
 |     /**
 | ||||||
|      * Constructor |      * Constructor | ||||||
|  | @ -65,7 +63,7 @@ namespace gtsam { | ||||||
|      * @param pointKey is the index of the landmark |      * @param pointKey is the index of the landmark | ||||||
|      * @param K shared pointer to the constant calibration |      * @param K shared pointer to the constant calibration | ||||||
|      */ |      */ | ||||||
|     TransformCalProjectionFactor(const Point2& measured, const SharedNoiseModel& model, |     ProjectionFactorPPPC(const Point2& measured, const SharedNoiseModel& model, | ||||||
|         Key poseKey, Key transformKey,  Key pointKey, Key calibKey) : |         Key poseKey, Key transformKey,  Key pointKey, Key calibKey) : | ||||||
|           Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured), |           Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured), | ||||||
|           throwCheirality_(false), verboseCheirality_(false) {} |           throwCheirality_(false), verboseCheirality_(false) {} | ||||||
|  | @ -81,14 +79,14 @@ namespace gtsam { | ||||||
|      * @param throwCheirality determines whether Cheirality exceptions are rethrown |      * @param throwCheirality determines whether Cheirality exceptions are rethrown | ||||||
|      * @param verboseCheirality determines whether exceptions are printed for Cheirality |      * @param verboseCheirality determines whether exceptions are printed for Cheirality | ||||||
|      */ |      */ | ||||||
|     TransformCalProjectionFactor(const Point2& measured, const SharedNoiseModel& model, |     ProjectionFactorPPPC(const Point2& measured, const SharedNoiseModel& model, | ||||||
|         Key poseKey, Key transformKey, Key pointKey, Key calibKey, |         Key poseKey, Key transformKey, Key pointKey, Key calibKey, | ||||||
|         bool throwCheirality, bool verboseCheirality) : |         bool throwCheirality, bool verboseCheirality) : | ||||||
|           Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured), |           Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured), | ||||||
|           throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} |           throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} | ||||||
| 
 | 
 | ||||||
|     /** Virtual destructor */ |     /** Virtual destructor */ | ||||||
|     virtual ~TransformCalProjectionFactor() {} |     virtual ~ProjectionFactorPPPC() {} | ||||||
| 
 | 
 | ||||||
|     /// @return a deep copy of this factor
 |     /// @return a deep copy of this factor
 | ||||||
|     virtual gtsam::NonlinearFactor::shared_ptr clone() const { |     virtual gtsam::NonlinearFactor::shared_ptr clone() const { | ||||||
|  | @ -101,7 +99,7 @@ namespace gtsam { | ||||||
|      * @param keyFormatter optional formatter useful for printing Symbols |      * @param keyFormatter optional formatter useful for printing Symbols | ||||||
|      */ |      */ | ||||||
|     void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { |     void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { | ||||||
|       std::cout << s << "TransformCalProjectionFactor, z = "; |       std::cout << s << "ProjectionFactorPPPC, z = "; | ||||||
|       measured_.print(); |       measured_.print(); | ||||||
|       Base::print("", keyFormatter); |       Base::print("", keyFormatter); | ||||||
|     } |     } | ||||||
|  | @ -10,7 +10,7 @@ | ||||||
|  * -------------------------------------------------------------------------- */ |  * -------------------------------------------------------------------------- */ | ||||||
| 
 | 
 | ||||||
| /**
 | /**
 | ||||||
|  *  @file  testTransformCalProjectionFactor.cpp |  *  @file  testProjectionFactorPPPC.cpp | ||||||
|  *  @brief Unit tests for Pose+Transform+Calibration ProjectionFactor Class |  *  @brief Unit tests for Pose+Transform+Calibration ProjectionFactor Class | ||||||
|  *  @author Chris Beall |  *  @author Chris Beall | ||||||
|  *  @date Jul 29, 2014 |  *  @date Jul 29, 2014 | ||||||
|  | @ -18,7 +18,7 @@ | ||||||
| 
 | 
 | ||||||
| #include <gtsam/base/numericalDerivative.h> | #include <gtsam/base/numericalDerivative.h> | ||||||
| #include <gtsam/base/TestableAssertions.h> | #include <gtsam/base/TestableAssertions.h> | ||||||
| #include <gtsam_unstable/slam/TransformCalProjectionFactor.h> | #include <gtsam_unstable/slam/ProjectionFactorPPPC.h> | ||||||
| #include <gtsam/inference/Symbol.h> | #include <gtsam/inference/Symbol.h> | ||||||
| #include <gtsam/geometry/Cal3DS2.h> | #include <gtsam/geometry/Cal3DS2.h> | ||||||
| #include <gtsam/geometry/Cal3_S2.h> | #include <gtsam/geometry/Cal3_S2.h> | ||||||
|  | @ -47,11 +47,11 @@ using symbol_shorthand::L; | ||||||
| using symbol_shorthand::T; | using symbol_shorthand::T; | ||||||
| using symbol_shorthand::K; | using symbol_shorthand::K; | ||||||
| 
 | 
 | ||||||
| typedef TransformCalProjectionFactor<Pose3, Point3, Cal3_S2> TestProjectionFactor; | typedef ProjectionFactorPPPC<Pose3, Point3, Cal3_S2> TestProjectionFactor; | ||||||
| 
 | 
 | ||||||
| /* ************************************************************************* */ | /* ************************************************************************* */ | ||||||
| TEST( ProjectionFactor, nonStandard ) { | TEST( ProjectionFactor, nonStandard ) { | ||||||
|   TransformCalProjectionFactor<Pose3, Point3, Cal3DS2> f; |   ProjectionFactorPPPC<Pose3, Point3, Cal3DS2> f; | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| /* ************************************************************************* */ | /* ************************************************************************* */ | ||||||
		Loading…
	
		Reference in New Issue