diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 9c7561f61..9e7b4c327 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -18,6 +18,7 @@ #pragma once +#include #include namespace gtsam { @@ -27,7 +28,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ -class Cal3Bundler { +class Cal3Bundler : public DerivedValue { private: double f_, k1_, k2_ ; diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 437a68a68..86a397daa 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -18,6 +18,7 @@ #pragma once +#include #include namespace gtsam { @@ -27,7 +28,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ -class Cal3DS2 { +class Cal3DS2 : public DerivedValue { private: diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index 71adc58bc..29b905932 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -21,6 +21,7 @@ #pragma once +#include #include namespace gtsam { @@ -30,7 +31,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ - class Cal3_S2 { + class Cal3_S2 : public DerivedValue { private: double fx_, fy_, s_, u0_, v0_; diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index a8366e35f..31265fbac 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -26,7 +26,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ - class Cal3_S2Stereo: public Cal3_S2 { + class Cal3_S2Stereo: public DerivedValue, public Cal3_S2 { private: double b_; diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index a53cb52df..f1e647046 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include @@ -35,7 +36,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ - class CalibratedCamera { + class CalibratedCamera : public DerivedValue { private: Pose3 pose_; // 6DOF pose diff --git a/gtsam/geometry/CalibratedCameraT.h b/gtsam/geometry/CalibratedCameraT.h index 6a70905a4..fde771398 100644 --- a/gtsam/geometry/CalibratedCameraT.h +++ b/gtsam/geometry/CalibratedCameraT.h @@ -8,6 +8,8 @@ #pragma once #include + +#include #include #include @@ -23,7 +25,7 @@ namespace gtsam { * \nosubgrouping */ template - class CalibratedCameraT { + class CalibratedCameraT : public DerivedValue > { private: Pose3 pose_; // 6DOF pose Calibration k_; diff --git a/gtsam/geometry/GeneralCameraT.h b/gtsam/geometry/GeneralCameraT.h index d93c56472..6852fa475 100644 --- a/gtsam/geometry/GeneralCameraT.h +++ b/gtsam/geometry/GeneralCameraT.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include #include @@ -31,7 +32,7 @@ namespace gtsam { * \nosubgrouping */ template -class GeneralCameraT { +class GeneralCameraT : public DerivedValue > { private: Camera calibrated_; // Calibrated camera diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 558d8bd4d..4a8be8edf 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -18,6 +18,8 @@ #pragma once #include + +#include #include #include @@ -30,7 +32,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ -class Point2 { +class Point2 : DerivedValue { public: /// dimension of the variable - used to autodetect sizes static const size_t dimension = 2; diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 269331490..73274c676 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -24,6 +24,7 @@ #include #include +#include #include namespace gtsam { @@ -33,7 +34,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ - class Point3 { + class Point3 : public DerivedValue { public: /// dimension of the variable - used to autodetect sizes static const size_t dimension = 3; diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 506ae59c9..85b2826dc 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -22,6 +22,7 @@ #include #include +#include #include #include @@ -32,7 +33,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ -class Pose2 { +class Pose2 : public DerivedValue { public: static const size_t dimension = 3; diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 48933a691..2cf836800 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -22,6 +22,7 @@ #define POSE3_DEFAULT_COORDINATES_MODE Pose3::FIRST_ORDER #endif +#include #include #include @@ -34,7 +35,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ - class Pose3 { + class Pose3 : public DerivedValue { public: static const size_t dimension = 6; diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index eb6d1f1e9..b8cb4255d 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -19,6 +19,8 @@ #pragma once #include + +#include #include namespace gtsam { @@ -29,7 +31,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ - class Rot2 { + class Rot2 : public DerivedValue { public: /** get the dimension by the type */ diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index 88eabb0f5..ae80ad96e 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include @@ -29,7 +30,7 @@ namespace gtsam { * to produce measurements in pixels. * Not a sublass as a SimpleCamera *is not* a CalibratedCamera. */ - class SimpleCamera { + class SimpleCamera : public DerivedValue { private: CalibratedCamera calibrated_; // Calibrated camera Cal3_S2 K_; // Calibration diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index cd3dbd19e..f5e07e66c 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -18,6 +18,8 @@ #pragma once #include + +#include #include #include #include diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 0bdf37e0e..63538b6d5 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -18,6 +18,7 @@ #pragma once +#include #include namespace gtsam { @@ -27,7 +28,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ - class StereoPoint2 { + class StereoPoint2 : public DerivedValue { public: static const size_t dimension = 3; private: