Remove landmark template parameter

release/4.3a0
cbeall3 2014-11-19 13:07:14 -05:00
parent 6529b793cc
commit dd255eb24c
6 changed files with 21 additions and 19 deletions

View File

@ -61,8 +61,7 @@ using namespace std;
using namespace gtsam;
// Make the typename short so it looks much cleaner
typedef gtsam::SmartProjectionPoseFactor<gtsam::Pose3, gtsam::Point3,
gtsam::Cal3_S2> SmartFactor;
typedef gtsam::SmartProjectionPoseFactor<gtsam::Pose3, gtsam::Cal3_S2> SmartFactor;
/* ************************************************************************* */
int main(int argc, char* argv[]) {

View File

@ -48,7 +48,7 @@ protected:
boost::optional<POSE> body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras)
static const int ZDim = traits::dimension<Z>::value; ///< Dimension trait of measurement type
static const int ZDim = traits::dimension<Z>::value; ///< Measurement dimension
/// Definitions for blocks of F
typedef Eigen::Matrix<double, ZDim, D> Matrix2D; // F

View File

@ -61,7 +61,7 @@ enum LinearizationMode {
* SmartProjectionFactor: triangulates point
* TODO: why LANDMARK parameter?
*/
template<class POSE, class LANDMARK, class CALIBRATION, size_t D>
template<class POSE, class CALIBRATION, size_t D>
class SmartProjectionFactor: public SmartFactorBase<POSE, gtsam::Point2, gtsam::PinholeCamera<CALIBRATION>, D> {
protected:
@ -102,9 +102,9 @@ protected:
// and the factor is disregarded if the error is large
/// shorthand for this class
typedef SmartProjectionFactor<POSE, LANDMARK, CALIBRATION, D> This;
typedef SmartProjectionFactor<POSE, CALIBRATION, D> This;
typedef traits::dimension<gtsam::Point2> ZDim_t; ///< Dimension trait of measurement type
static const int ZDim = traits::dimension<Point2>::value; ///< Measurement dimension
public:
@ -420,16 +420,16 @@ public:
}
/// create factor
boost::shared_ptr<JacobianFactorQ<D, ZDim_t::value> > createJacobianQFactor(
boost::shared_ptr<JacobianFactorQ<D, ZDim> > createJacobianQFactor(
const Cameras& cameras, double lambda) const {
if (triangulateForLinearize(cameras))
return Base::createJacobianQFactor(cameras, point_, lambda);
else
return boost::make_shared< JacobianFactorQ<D, ZDim_t::value> >(this->keys_);
return boost::make_shared< JacobianFactorQ<D, ZDim> >(this->keys_);
}
/// Create a factor, takes values
boost::shared_ptr<JacobianFactorQ<D, ZDim_t::value> > createJacobianQFactor(
boost::shared_ptr<JacobianFactorQ<D, ZDim> > createJacobianQFactor(
const Values& values, double lambda) const {
Cameras myCameras;
// TODO triangulate twice ??
@ -437,7 +437,7 @@ public:
if (nonDegenerate)
return createJacobianQFactor(myCameras, lambda);
else
return boost::make_shared< JacobianFactorQ<D, ZDim_t::value> >(this->keys_);
return boost::make_shared< JacobianFactorQ<D, ZDim> >(this->keys_);
}
/// different (faster) way to compute Jacobian factor
@ -446,7 +446,7 @@ public:
if (triangulateForLinearize(cameras))
return Base::createJacobianSVDFactor(cameras, point_, lambda);
else
return boost::make_shared< JacobianFactorSVD<D, ZDim_t::value> >(this->keys_);
return boost::make_shared< JacobianFactorSVD<D, ZDim> >(this->keys_);
}
/// Returns true if nonDegenerate
@ -709,4 +709,7 @@ private:
}
};
template<class POSE, class CALIBRATION, size_t D>
const int SmartProjectionFactor<POSE, CALIBRATION, D>::ZDim;
} // \ namespace gtsam

View File

@ -37,8 +37,8 @@ namespace gtsam {
* The calibration is known here. The factor only constraints poses (variable dimension is 6)
* @addtogroup SLAM
*/
template<class POSE, class LANDMARK, class CALIBRATION>
class SmartProjectionPoseFactor: public SmartProjectionFactor<POSE, LANDMARK, CALIBRATION, 6> {
template<class POSE, class CALIBRATION>
class SmartProjectionPoseFactor: public SmartProjectionFactor<POSE, CALIBRATION, 6> {
protected:
LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q)
@ -48,10 +48,10 @@ protected:
public:
/// shorthand for base class type
typedef SmartProjectionFactor<POSE, LANDMARK, CALIBRATION, 6> Base;
typedef SmartProjectionFactor<POSE, CALIBRATION, 6> Base;
/// shorthand for this class
typedef SmartProjectionPoseFactor<POSE, LANDMARK, CALIBRATION> This;
typedef SmartProjectionPoseFactor<POSE, CALIBRATION> This;
/// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<This> shared_ptr;

View File

@ -60,8 +60,8 @@ static Key poseKey1(x1);
static Point2 measurement1(323.0, 240.0);
static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0));
typedef SmartProjectionPoseFactor<Pose3,Point3,Cal3_S2> SmartFactor;
typedef SmartProjectionPoseFactor<Pose3,Point3,Cal3Bundler> SmartFactorBundler;
typedef SmartProjectionPoseFactor<Pose3,Cal3_S2> SmartFactor;
typedef SmartProjectionPoseFactor<Pose3,Cal3Bundler> SmartFactorBundler;
void projectToMultipleCameras(
SimpleCamera cam1, SimpleCamera cam2, SimpleCamera cam3, Point3 landmark,
@ -1202,7 +1202,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ){
/* ************************************************************************* */
TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) {
SmartProjectionPoseFactor<Pose3,Point3,Cal3Bundler> factor1(rankTol, linThreshold);
SmartProjectionPoseFactor<Pose3,Cal3Bundler> factor1(rankTol, linThreshold);
boost::shared_ptr<Cal3Bundler> Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000));
factor1.add(measurement1, poseKey1, model, Kbundler);
}

View File

@ -46,7 +46,7 @@ using namespace gtsam;
int main(int argc, char** argv){
typedef SmartProjectionPoseFactor<Pose3, Point3, Cal3_S2> SmartFactor;
typedef SmartProjectionPoseFactor<Pose3, Cal3_S2> SmartFactor;
Values initial_estimate;
NonlinearFactorGraph graph;