Remove landmark template parameter
parent
6529b793cc
commit
dd255eb24c
|
@ -61,8 +61,7 @@ using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
||||||
// Make the typename short so it looks much cleaner
|
// Make the typename short so it looks much cleaner
|
||||||
typedef gtsam::SmartProjectionPoseFactor<gtsam::Pose3, gtsam::Point3,
|
typedef gtsam::SmartProjectionPoseFactor<gtsam::Pose3, gtsam::Cal3_S2> SmartFactor;
|
||||||
gtsam::Cal3_S2> SmartFactor;
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main(int argc, char* argv[]) {
|
int main(int argc, char* argv[]) {
|
||||||
|
|
|
@ -48,7 +48,7 @@ protected:
|
||||||
|
|
||||||
boost::optional<POSE> body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras)
|
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
|
/// Definitions for blocks of F
|
||||||
typedef Eigen::Matrix<double, ZDim, D> Matrix2D; // F
|
typedef Eigen::Matrix<double, ZDim, D> Matrix2D; // F
|
||||||
|
|
|
@ -61,7 +61,7 @@ enum LinearizationMode {
|
||||||
* SmartProjectionFactor: triangulates point
|
* SmartProjectionFactor: triangulates point
|
||||||
* TODO: why LANDMARK parameter?
|
* 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> {
|
class SmartProjectionFactor: public SmartFactorBase<POSE, gtsam::Point2, gtsam::PinholeCamera<CALIBRATION>, D> {
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
@ -102,9 +102,9 @@ protected:
|
||||||
// and the factor is disregarded if the error is large
|
// and the factor is disregarded if the error is large
|
||||||
|
|
||||||
/// shorthand for this class
|
/// 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:
|
public:
|
||||||
|
|
||||||
|
@ -420,16 +420,16 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
/// create factor
|
/// create factor
|
||||||
boost::shared_ptr<JacobianFactorQ<D, ZDim_t::value> > createJacobianQFactor(
|
boost::shared_ptr<JacobianFactorQ<D, ZDim> > createJacobianQFactor(
|
||||||
const Cameras& cameras, double lambda) const {
|
const Cameras& cameras, double lambda) const {
|
||||||
if (triangulateForLinearize(cameras))
|
if (triangulateForLinearize(cameras))
|
||||||
return Base::createJacobianQFactor(cameras, point_, lambda);
|
return Base::createJacobianQFactor(cameras, point_, lambda);
|
||||||
else
|
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
|
/// 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 {
|
const Values& values, double lambda) const {
|
||||||
Cameras myCameras;
|
Cameras myCameras;
|
||||||
// TODO triangulate twice ??
|
// TODO triangulate twice ??
|
||||||
|
@ -437,7 +437,7 @@ public:
|
||||||
if (nonDegenerate)
|
if (nonDegenerate)
|
||||||
return createJacobianQFactor(myCameras, lambda);
|
return createJacobianQFactor(myCameras, lambda);
|
||||||
else
|
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
|
/// different (faster) way to compute Jacobian factor
|
||||||
|
@ -446,7 +446,7 @@ public:
|
||||||
if (triangulateForLinearize(cameras))
|
if (triangulateForLinearize(cameras))
|
||||||
return Base::createJacobianSVDFactor(cameras, point_, lambda);
|
return Base::createJacobianSVDFactor(cameras, point_, lambda);
|
||||||
else
|
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
|
/// 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
|
} // \ namespace gtsam
|
||||||
|
|
|
@ -37,8 +37,8 @@ namespace gtsam {
|
||||||
* The calibration is known here. The factor only constraints poses (variable dimension is 6)
|
* The calibration is known here. The factor only constraints poses (variable dimension is 6)
|
||||||
* @addtogroup SLAM
|
* @addtogroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class POSE, class LANDMARK, class CALIBRATION>
|
template<class POSE, class CALIBRATION>
|
||||||
class SmartProjectionPoseFactor: public SmartProjectionFactor<POSE, LANDMARK, CALIBRATION, 6> {
|
class SmartProjectionPoseFactor: public SmartProjectionFactor<POSE, CALIBRATION, 6> {
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q)
|
LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q)
|
||||||
|
@ -48,10 +48,10 @@ protected:
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/// shorthand for base class type
|
/// shorthand for base class type
|
||||||
typedef SmartProjectionFactor<POSE, LANDMARK, CALIBRATION, 6> Base;
|
typedef SmartProjectionFactor<POSE, CALIBRATION, 6> Base;
|
||||||
|
|
||||||
/// shorthand for this class
|
/// shorthand for this class
|
||||||
typedef SmartProjectionPoseFactor<POSE, LANDMARK, CALIBRATION> This;
|
typedef SmartProjectionPoseFactor<POSE, 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;
|
||||||
|
|
|
@ -60,8 +60,8 @@ static Key poseKey1(x1);
|
||||||
static Point2 measurement1(323.0, 240.0);
|
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));
|
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,Cal3_S2> SmartFactor;
|
||||||
typedef SmartProjectionPoseFactor<Pose3,Point3,Cal3Bundler> SmartFactorBundler;
|
typedef SmartProjectionPoseFactor<Pose3,Cal3Bundler> SmartFactorBundler;
|
||||||
|
|
||||||
void projectToMultipleCameras(
|
void projectToMultipleCameras(
|
||||||
SimpleCamera cam1, SimpleCamera cam2, SimpleCamera cam3, Point3 landmark,
|
SimpleCamera cam1, SimpleCamera cam2, SimpleCamera cam3, Point3 landmark,
|
||||||
|
@ -1202,7 +1202,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ){
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) {
|
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));
|
boost::shared_ptr<Cal3Bundler> Kbundler(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000));
|
||||||
factor1.add(measurement1, poseKey1, model, Kbundler);
|
factor1.add(measurement1, poseKey1, model, Kbundler);
|
||||||
}
|
}
|
||||||
|
|
|
@ -46,7 +46,7 @@ using namespace gtsam;
|
||||||
|
|
||||||
int main(int argc, char** argv){
|
int main(int argc, char** argv){
|
||||||
|
|
||||||
typedef SmartProjectionPoseFactor<Pose3, Point3, Cal3_S2> SmartFactor;
|
typedef SmartProjectionPoseFactor<Pose3, Cal3_S2> SmartFactor;
|
||||||
|
|
||||||
Values initial_estimate;
|
Values initial_estimate;
|
||||||
NonlinearFactorGraph graph;
|
NonlinearFactorGraph graph;
|
||||||
|
|
Loading…
Reference in New Issue