template base class on Camera instead of Calibration
parent
c583564098
commit
6d33b3c24e
|
|
@ -36,7 +36,7 @@
|
|||
|
||||
namespace gtsam {
|
||||
/// Base class with no internal point, completely functional
|
||||
template<class POSE, class Z, class CALIBRATION, size_t D>
|
||||
template<class POSE, class Z, class CAMERA, size_t D>
|
||||
class SmartFactorBase: public NonlinearFactor {
|
||||
|
||||
protected:
|
||||
|
|
@ -61,7 +61,7 @@ protected:
|
|||
typedef NonlinearFactor Base;
|
||||
|
||||
/// shorthand for this class
|
||||
typedef SmartFactorBase<POSE, Z, CALIBRATION, D> This;
|
||||
typedef SmartFactorBase<POSE, Z, CAMERA, D> This;
|
||||
|
||||
public:
|
||||
|
||||
|
|
@ -69,8 +69,7 @@ public:
|
|||
typedef boost::shared_ptr<This> shared_ptr;
|
||||
|
||||
/// shorthand for a pinhole camera
|
||||
typedef PinholeCamera<CALIBRATION> Camera;
|
||||
typedef std::vector<Camera> Cameras;
|
||||
typedef std::vector<CAMERA> Cameras;
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
|
|
@ -216,7 +215,7 @@ public:
|
|||
double overallError = 0;
|
||||
|
||||
size_t i = 0;
|
||||
BOOST_FOREACH(const Camera& camera, cameras) {
|
||||
BOOST_FOREACH(const CAMERA& camera, cameras) {
|
||||
const Z& zi = this->measured_.at(i);
|
||||
try {
|
||||
Z reprojectionError(camera.project(point) - zi);
|
||||
|
|
|
|||
|
|
@ -62,7 +62,7 @@ enum LinearizationMode {
|
|||
* TODO: why LANDMARK parameter?
|
||||
*/
|
||||
template<class POSE, class LANDMARK, class CALIBRATION, size_t D>
|
||||
class SmartProjectionFactor: public SmartFactorBase<POSE, gtsam::Point2, CALIBRATION, D> {
|
||||
class SmartProjectionFactor: public SmartFactorBase<POSE, gtsam::Point2, gtsam::PinholeCamera<CALIBRATION>, D> {
|
||||
protected:
|
||||
|
||||
// Some triangulation parameters
|
||||
|
|
@ -92,7 +92,7 @@ protected:
|
|||
typedef boost::shared_ptr<SmartProjectionFactorState> SmartFactorStatePtr;
|
||||
|
||||
/// shorthand for base class type
|
||||
typedef SmartFactorBase<POSE, gtsam::Point2, CALIBRATION, D> Base;
|
||||
typedef SmartFactorBase<POSE, gtsam::Point2, gtsam::PinholeCamera<CALIBRATION>, D> Base;
|
||||
|
||||
double landmarkDistanceThreshold_; // if the landmark is triangulated at a
|
||||
// distance larger than that the factor is considered degenerate
|
||||
|
|
|
|||
|
|
@ -62,7 +62,7 @@ enum LinearizationMode {
|
|||
* TODO: why LANDMARK parameter?
|
||||
*/
|
||||
template<class POSE, class LANDMARK, class CALIBRATION, size_t D>
|
||||
class SmartStereoProjectionFactor: public SmartFactorBase<POSE, gtsam::Point2, CALIBRATION, D> {
|
||||
class SmartStereoProjectionFactor: public SmartFactorBase<POSE, gtsam::Point2, gtsam::PinholeCamera<CALIBRATION>, D> {
|
||||
protected:
|
||||
|
||||
// Some triangulation parameters
|
||||
|
|
@ -92,7 +92,7 @@ protected:
|
|||
typedef boost::shared_ptr<SmartStereoProjectionFactorState> SmartFactorStatePtr;
|
||||
|
||||
/// shorthand for base class type
|
||||
typedef SmartFactorBase<POSE, gtsam::Point2, CALIBRATION, D> Base;
|
||||
typedef SmartFactorBase<POSE, gtsam::Point2, gtsam::PinholeCamera<CALIBRATION>, D> Base;
|
||||
|
||||
double landmarkDistanceThreshold_; // if the landmark is triangulated at a
|
||||
// distance larger than that the factor is considered degenerate
|
||||
|
|
|
|||
Loading…
Reference in New Issue