diff --git a/gtsam/base/LieMatrix.h b/gtsam/base/LieMatrix.h index 2a8d4bc41..cd8489bbc 100644 --- a/gtsam/base/LieMatrix.h +++ b/gtsam/base/LieMatrix.h @@ -29,7 +29,7 @@ namespace gtsam { /** * LieVector is a wrapper around vector to allow it to be a Lie type */ -struct LieMatrix : public Matrix, public DerivedValue { +struct LieMatrix : public Matrix { /// @name Constructors /// @{ @@ -166,8 +166,7 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("LieMatrix", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("LieMatrix",*this); ar & boost::serialization::make_nvp("Matrix", boost::serialization::base_object(*this)); diff --git a/gtsam/base/LieScalar.h b/gtsam/base/LieScalar.h index 750a8a21f..b91d3ca2f 100644 --- a/gtsam/base/LieScalar.h +++ b/gtsam/base/LieScalar.h @@ -26,7 +26,7 @@ namespace gtsam { /** * LieScalar is a wrapper around double to allow it to be a Lie type */ - struct GTSAM_EXPORT LieScalar : public DerivedValue { + struct GTSAM_EXPORT LieScalar { /** default constructor */ LieScalar() : d_(0.0) {} diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 8286c95a6..808a47c2c 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -26,7 +26,7 @@ namespace gtsam { /** * LieVector is a wrapper around vector to allow it to be a Lie type */ -struct LieVector : public Vector, public DerivedValue { +struct LieVector : public Vector { /** default constructor - should be unnecessary */ LieVector() {} @@ -123,8 +123,7 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("LieVector", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("LieVector",*this); ar & boost::serialization::make_nvp("Vector", boost::serialization::base_object(*this)); } diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 793f195d5..375749e69 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -28,7 +28,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Cal3Bundler: public DerivedValue { +class GTSAM_EXPORT Cal3Bundler { private: double f_; ///< focal length @@ -173,8 +173,7 @@ private: template void serialize(Archive & ar, const unsigned int version) { ar - & boost::serialization::make_nvp("Cal3Bundler", - boost::serialization::base_object(*this)); + & boost::serialization::make_nvp("Cal3Bundler",*this); ar & BOOST_SERIALIZATION_NVP(f_); ar & BOOST_SERIALIZATION_NVP(k1_); ar & BOOST_SERIALIZATION_NVP(k2_); diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index d716d398e..0ef34005d 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -37,7 +37,7 @@ namespace gtsam { * k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] * pi = K*pn */ -class GTSAM_EXPORT Cal3DS2 : public DerivedValue { +class GTSAM_EXPORT Cal3DS2 { protected: @@ -153,8 +153,7 @@ private: template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Cal3DS2", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Cal3DS2",*this); ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(s_); diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index a87a30e36..2f3a61bce 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -31,7 +31,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Cal3_S2: public DerivedValue { +class GTSAM_EXPORT Cal3_S2 { private: double fx_, fy_, s_, u0_, v0_; @@ -227,8 +227,7 @@ private: template void serialize(Archive & ar, const unsigned int version) { ar - & boost::serialization::make_nvp("Cal3_S2", - boost::serialization::base_object(*this)); + & boost::serialization::make_nvp("Cal3_S2",*this); ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(s_); diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 6e7b5a114..0e781fbc1 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -39,7 +39,7 @@ public: * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT CalibratedCamera: public DerivedValue { +class GTSAM_EXPORT CalibratedCamera { private: Pose3 pose_; // 6DOF pose @@ -215,8 +215,7 @@ private: template void serialize(Archive & ar, const unsigned int version) { ar - & boost::serialization::make_nvp("CalibratedCamera", - boost::serialization::base_object(*this)); + & boost::serialization::make_nvp("CalibratedCamera",*this); ar & BOOST_SERIALIZATION_NVP(pose_); } diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index a973f9cec..48a0fead6 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -20,7 +20,7 @@ namespace gtsam { * but here we choose instead to parameterize it as a (Rot3,Unit3) pair. * We can then non-linearly optimize immediately on this 5-dimensional manifold. */ -class GTSAM_EXPORT EssentialMatrix: public DerivedValue { +class GTSAM_EXPORT EssentialMatrix { private: @@ -176,8 +176,7 @@ private: friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("EssentialMatrix", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("EssentialMatrix",*this); ar & BOOST_SERIALIZATION_NVP(aRb_); ar & BOOST_SERIALIZATION_NVP(aTb_); diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index c2fea07e0..a6c1c6f42 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -37,7 +37,7 @@ namespace gtsam { * \nosubgrouping */ template -class PinholeCamera: public DerivedValue > { +class PinholeCamera { private: Pose3 pose_; Calibration K_; diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 7d1fab133..56570723d 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -32,7 +32,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Point2 : public DerivedValue { +class GTSAM_EXPORT Point2 { private: @@ -237,8 +237,7 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Point2", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Point2",*this); ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(y_); } diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index d69ceb861..7739f3d9c 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -36,7 +36,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT Point3 : public DerivedValue { + class GTSAM_EXPORT Point3 { private: @@ -228,8 +228,7 @@ namespace gtsam { template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Point3", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Point3",*this); ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(y_); ar & BOOST_SERIALIZATION_NVP(z_); diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index b6a2314ff..f1cd6bd3f 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -33,7 +33,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Pose2 : public DerivedValue { +class GTSAM_EXPORT Pose2 { public: @@ -301,8 +301,7 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Pose2", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Pose2",*this); ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(r_); } diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 5f99b25ac..57132b453 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -39,7 +39,7 @@ class Pose2; * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Pose3: public DerivedValue { +class GTSAM_EXPORT Pose3{ public: /** Pose Concept requirements */ @@ -326,8 +326,7 @@ public: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Pose3", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Pose3",*this); ar & BOOST_SERIALIZATION_NVP(R_); ar & BOOST_SERIALIZATION_NVP(t_); } diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 4142d4473..55f7bad50 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -31,7 +31,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT Rot2 : public DerivedValue { + class GTSAM_EXPORT Rot2 { public: /** get the dimension by the type */ @@ -235,8 +235,7 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Rot2", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Rot2",*this); ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(s_); } diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 7215e159f..88c0fe370 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -58,7 +58,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT Rot3 : public DerivedValue { + class GTSAM_EXPORT Rot3 { private: @@ -456,8 +456,7 @@ namespace gtsam { template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Rot3", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Rot3",*this); #ifndef GTSAM_USE_QUATERNIONS ar & boost::serialization::make_nvp("rot11", rot_(0,0)); ar & boost::serialization::make_nvp("rot12", rot_(0,1)); diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index 82914f6ab..ca0377c1b 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -36,7 +36,7 @@ public: * A stereo camera class, parameterize by left camera pose and stereo calibration * @addtogroup geometry */ -class GTSAM_EXPORT StereoCamera : public DerivedValue { +class GTSAM_EXPORT StereoCamera { private: Pose3 leftCamPose_; @@ -147,8 +147,7 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("StereoCamera", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("StereoCamera",*this); ar & BOOST_SERIALIZATION_NVP(leftCamPose_); ar & BOOST_SERIALIZATION_NVP(K_); } diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 000f7d16f..9da456b60 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -28,7 +28,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT StereoPoint2 : public DerivedValue { + class GTSAM_EXPORT StereoPoint2 { public: static const size_t dimension = 3; private: @@ -162,8 +162,7 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("StereoPoint2", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("StereoPoint2",*this); ar & BOOST_SERIALIZATION_NVP(uL_); ar & BOOST_SERIALIZATION_NVP(uR_); ar & BOOST_SERIALIZATION_NVP(v_); diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index bb2ee318a..6a84e014c 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -27,7 +27,7 @@ namespace gtsam { /// Represents a 3D point on a unit sphere. -class GTSAM_EXPORT Unit3: public DerivedValue { +class GTSAM_EXPORT Unit3{ private: @@ -146,8 +146,7 @@ private: friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Unit3", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("Unit3",*this); ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(B_); } diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 8301a0a6b..c08a37905 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -39,7 +39,7 @@ namespace gtsam { /// All bias models live in the imuBias namespace namespace imuBias { - class ConstantBias : public DerivedValue { + class ConstantBias { private: Vector3 biasAcc_; Vector3 biasGyro_; @@ -205,8 +205,7 @@ namespace imuBias { template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("imuBias::ConstantBias", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("imuBias::ConstantBias",*this); ar & BOOST_SERIALIZATION_NVP(biasAcc_); ar & BOOST_SERIALIZATION_NVP(biasGyro_); } diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 041ea0387..a8b7b612f 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -51,7 +51,7 @@ public: }; int TestValueData::ConstructorCount = 0; int TestValueData::DestructorCount = 0; -class TestValue : public DerivedValue { +class TestValue { TestValueData data_; public: virtual void print(const std::string& str = "") const {} diff --git a/gtsam_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index 80729e8a2..04da7c513 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -19,7 +19,7 @@ typedef Point3 Velocity3; * Robot state for use with IMU measurements * - contains translation, translational velocity and rotation */ -class GTSAM_UNSTABLE_EXPORT PoseRTV : public DerivedValue { +class GTSAM_UNSTABLE_EXPORT PoseRTV { protected: Pose3 Rt_; diff --git a/gtsam_unstable/geometry/BearingS2.h b/gtsam_unstable/geometry/BearingS2.h index d48490ccc..4c84bbe56 100644 --- a/gtsam_unstable/geometry/BearingS2.h +++ b/gtsam_unstable/geometry/BearingS2.h @@ -15,7 +15,7 @@ namespace gtsam { -class GTSAM_UNSTABLE_EXPORT BearingS2 : public DerivedValue { +class GTSAM_UNSTABLE_EXPORT BearingS2 { protected: Rot2 azimuth_, elevation_; diff --git a/gtsam_unstable/geometry/Pose3Upright.h b/gtsam_unstable/geometry/Pose3Upright.h index c1e12b4a7..a2db1d176 100644 --- a/gtsam_unstable/geometry/Pose3Upright.h +++ b/gtsam_unstable/geometry/Pose3Upright.h @@ -22,7 +22,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ -class GTSAM_UNSTABLE_EXPORT Pose3Upright : public DerivedValue { +class GTSAM_UNSTABLE_EXPORT Pose3Upright { public: static const size_t dimension = 4;