Renamed TransformCalProjectionFactor to ProjectionFactorPPPC to follow new naming convention

release/4.3a0
Chris Beall 2014-08-12 15:29:05 -04:00
parent bc982293ab
commit 2c3f6e563d
3 changed files with 24 additions and 26 deletions

View File

@ -767,13 +767,13 @@ typedef gtsam::TransformProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal
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>
virtual class TransformCalProjectionFactor : gtsam::NoiseModelFactor {
TransformCalProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor {
ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
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);
gtsam::Point2 measured() const;
@ -783,7 +783,7 @@ virtual class TransformCalProjectionFactor : gtsam::NoiseModelFactor {
// enabling serialization functionality
void serialize() const;
};
typedef gtsam::TransformCalProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> TransformCalProjectionFactorCal3_S2;
typedef gtsam::TransformCalProjectionFactor<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> TransformCalProjectionFactorCal3DS2;
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCCal3_S2;
typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCCal3DS2;
} //\namespace gtsam

View File

@ -10,32 +10,30 @@
* -------------------------------------------------------------------------- */
/**
* @file TransformCalProjectionFactor.h
* @brief Basic bearing factor from 2D measurement
* @file ProjectionFactorPPPC.h
* @brief Derived from ProjectionFactor, but estimates body-camera transform
* and calibration in addition to body pose and 3D landmark
* @author Chris Beall
* @author Richard Roberts
* @author Frank Dellaert
* @author Alex Cunningham
*/
#pragma once
#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>
namespace gtsam {
/**
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
* i.e. the main building block for visual SLAM.
* Non-linear factor for a constraint derived from a 2D measurement. This factor
* estimates the body pose, body-camera transform, 3D landmark, and calibration.
* @addtogroup SLAM
*/
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:
// Keep a copy of measurement and calibration for I/O
Point2 measured_; ///< 2D measurement
// verbosity handling for Cheirality Exceptions
@ -48,13 +46,13 @@ namespace gtsam {
typedef NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> Base;
/// shorthand for this class
typedef TransformCalProjectionFactor<POSE, LANDMARK, CALIBRATION> This;
typedef ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> This;
/// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<This> shared_ptr;
/// Default constructor
TransformCalProjectionFactor() : throwCheirality_(false), verboseCheirality_(false) {}
ProjectionFactorPPPC() : throwCheirality_(false), verboseCheirality_(false) {}
/**
* Constructor
@ -65,7 +63,7 @@ namespace gtsam {
* @param pointKey is the index of the landmark
* @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) :
Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured),
throwCheirality_(false), verboseCheirality_(false) {}
@ -81,14 +79,14 @@ namespace gtsam {
* @param throwCheirality determines whether Cheirality exceptions are rethrown
* @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,
bool throwCheirality, bool verboseCheirality) :
Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured),
throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
/** Virtual destructor */
virtual ~TransformCalProjectionFactor() {}
virtual ~ProjectionFactorPPPC() {}
/// @return a deep copy of this factor
virtual gtsam::NonlinearFactor::shared_ptr clone() const {
@ -101,7 +99,7 @@ namespace gtsam {
* @param keyFormatter optional formatter useful for printing Symbols
*/
void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << "TransformCalProjectionFactor, z = ";
std::cout << s << "ProjectionFactorPPPC, z = ";
measured_.print();
Base::print("", keyFormatter);
}

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file testTransformCalProjectionFactor.cpp
* @file testProjectionFactorPPPC.cpp
* @brief Unit tests for Pose+Transform+Calibration ProjectionFactor Class
* @author Chris Beall
* @date Jul 29, 2014
@ -18,7 +18,7 @@
#include <gtsam/base/numericalDerivative.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/geometry/Cal3DS2.h>
#include <gtsam/geometry/Cal3_S2.h>
@ -47,11 +47,11 @@ using symbol_shorthand::L;
using symbol_shorthand::T;
using symbol_shorthand::K;
typedef TransformCalProjectionFactor<Pose3, Point3, Cal3_S2> TestProjectionFactor;
typedef ProjectionFactorPPPC<Pose3, Point3, Cal3_S2> TestProjectionFactor;
/* ************************************************************************* */
TEST( ProjectionFactor, nonStandard ) {
TransformCalProjectionFactor<Pose3, Point3, Cal3DS2> f;
ProjectionFactorPPPC<Pose3, Point3, Cal3DS2> f;
}
/* ************************************************************************* */