removed DerivedValue<> inheritence from classes

release/4.3a0
Mike Bosse 2014-10-24 18:34:06 +02:00
parent 0681212084
commit 1fadda83e0
23 changed files with 40 additions and 57 deletions

View File

@ -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<LieMatrix> {
struct LieMatrix : public Matrix {
/// @name Constructors
/// @{
@ -166,8 +166,7 @@ private:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("LieMatrix",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("LieMatrix",*this);
ar & boost::serialization::make_nvp("Matrix",
boost::serialization::base_object<Matrix>(*this));

View File

@ -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<LieScalar> {
struct GTSAM_EXPORT LieScalar {
/** default constructor */
LieScalar() : d_(0.0) {}

View File

@ -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<LieVector> {
struct LieVector : public Vector {
/** default constructor - should be unnecessary */
LieVector() {}
@ -123,8 +123,7 @@ private:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("LieVector",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("LieVector",*this);
ar & boost::serialization::make_nvp("Vector",
boost::serialization::base_object<Vector>(*this));
}

View File

@ -28,7 +28,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Cal3Bundler: public DerivedValue<Cal3Bundler> {
class GTSAM_EXPORT Cal3Bundler {
private:
double f_; ///< focal length
@ -173,8 +173,7 @@ private:
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar
& boost::serialization::make_nvp("Cal3Bundler",
boost::serialization::base_object<Value>(*this));
& boost::serialization::make_nvp("Cal3Bundler",*this);
ar & BOOST_SERIALIZATION_NVP(f_);
ar & BOOST_SERIALIZATION_NVP(k1_);
ar & BOOST_SERIALIZATION_NVP(k2_);

View File

@ -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<Cal3DS2> {
class GTSAM_EXPORT Cal3DS2 {
protected:
@ -153,8 +153,7 @@ private:
template<class Archive>
void serialize(Archive & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Cal3DS2",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("Cal3DS2",*this);
ar & BOOST_SERIALIZATION_NVP(fx_);
ar & BOOST_SERIALIZATION_NVP(fy_);
ar & BOOST_SERIALIZATION_NVP(s_);

View File

@ -31,7 +31,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Cal3_S2: public DerivedValue<Cal3_S2> {
class GTSAM_EXPORT Cal3_S2 {
private:
double fx_, fy_, s_, u0_, v0_;
@ -227,8 +227,7 @@ private:
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar
& boost::serialization::make_nvp("Cal3_S2",
boost::serialization::base_object<Value>(*this));
& boost::serialization::make_nvp("Cal3_S2",*this);
ar & BOOST_SERIALIZATION_NVP(fx_);
ar & BOOST_SERIALIZATION_NVP(fy_);
ar & BOOST_SERIALIZATION_NVP(s_);

View File

@ -39,7 +39,7 @@ public:
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT CalibratedCamera: public DerivedValue<CalibratedCamera> {
class GTSAM_EXPORT CalibratedCamera {
private:
Pose3 pose_; // 6DOF pose
@ -215,8 +215,7 @@ private:
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar
& boost::serialization::make_nvp("CalibratedCamera",
boost::serialization::base_object<Value>(*this));
& boost::serialization::make_nvp("CalibratedCamera",*this);
ar & BOOST_SERIALIZATION_NVP(pose_);
}

View File

@ -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<EssentialMatrix> {
class GTSAM_EXPORT EssentialMatrix {
private:
@ -176,8 +176,7 @@ private:
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("EssentialMatrix",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("EssentialMatrix",*this);
ar & BOOST_SERIALIZATION_NVP(aRb_);
ar & BOOST_SERIALIZATION_NVP(aTb_);

View File

@ -37,7 +37,7 @@ namespace gtsam {
* \nosubgrouping
*/
template<typename Calibration>
class PinholeCamera: public DerivedValue<PinholeCamera<Calibration> > {
class PinholeCamera {
private:
Pose3 pose_;
Calibration K_;

View File

@ -32,7 +32,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Point2 : public DerivedValue<Point2> {
class GTSAM_EXPORT Point2 {
private:
@ -237,8 +237,7 @@ private:
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Point2",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("Point2",*this);
ar & BOOST_SERIALIZATION_NVP(x_);
ar & BOOST_SERIALIZATION_NVP(y_);
}

View File

@ -36,7 +36,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Point3 : public DerivedValue<Point3> {
class GTSAM_EXPORT Point3 {
private:
@ -228,8 +228,7 @@ namespace gtsam {
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Point3",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("Point3",*this);
ar & BOOST_SERIALIZATION_NVP(x_);
ar & BOOST_SERIALIZATION_NVP(y_);
ar & BOOST_SERIALIZATION_NVP(z_);

View File

@ -33,7 +33,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Pose2 : public DerivedValue<Pose2> {
class GTSAM_EXPORT Pose2 {
public:
@ -301,8 +301,7 @@ private:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Pose2",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("Pose2",*this);
ar & BOOST_SERIALIZATION_NVP(t_);
ar & BOOST_SERIALIZATION_NVP(r_);
}

View File

@ -39,7 +39,7 @@ class Pose2;
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Pose3: public DerivedValue<Pose3> {
class GTSAM_EXPORT Pose3{
public:
/** Pose Concept requirements */
@ -326,8 +326,7 @@ public:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Pose3",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("Pose3",*this);
ar & BOOST_SERIALIZATION_NVP(R_);
ar & BOOST_SERIALIZATION_NVP(t_);
}

View File

@ -31,7 +31,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Rot2 : public DerivedValue<Rot2> {
class GTSAM_EXPORT Rot2 {
public:
/** get the dimension by the type */
@ -235,8 +235,7 @@ namespace gtsam {
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Rot2",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("Rot2",*this);
ar & BOOST_SERIALIZATION_NVP(c_);
ar & BOOST_SERIALIZATION_NVP(s_);
}

View File

@ -58,7 +58,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT Rot3 : public DerivedValue<Rot3> {
class GTSAM_EXPORT Rot3 {
private:
@ -456,8 +456,7 @@ namespace gtsam {
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Rot3",
boost::serialization::base_object<Value>(*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));

View File

@ -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<StereoCamera> {
class GTSAM_EXPORT StereoCamera {
private:
Pose3 leftCamPose_;
@ -147,8 +147,7 @@ private:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("StereoCamera",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("StereoCamera",*this);
ar & BOOST_SERIALIZATION_NVP(leftCamPose_);
ar & BOOST_SERIALIZATION_NVP(K_);
}

View File

@ -28,7 +28,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class GTSAM_EXPORT StereoPoint2 : public DerivedValue<StereoPoint2> {
class GTSAM_EXPORT StereoPoint2 {
public:
static const size_t dimension = 3;
private:
@ -162,8 +162,7 @@ namespace gtsam {
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("StereoPoint2",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("StereoPoint2",*this);
ar & BOOST_SERIALIZATION_NVP(uL_);
ar & BOOST_SERIALIZATION_NVP(uR_);
ar & BOOST_SERIALIZATION_NVP(v_);

View File

@ -27,7 +27,7 @@
namespace gtsam {
/// Represents a 3D point on a unit sphere.
class GTSAM_EXPORT Unit3: public DerivedValue<Unit3> {
class GTSAM_EXPORT Unit3{
private:
@ -146,8 +146,7 @@ private:
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Unit3",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("Unit3",*this);
ar & BOOST_SERIALIZATION_NVP(p_);
ar & BOOST_SERIALIZATION_NVP(B_);
}

View File

@ -39,7 +39,7 @@ namespace gtsam {
/// All bias models live in the imuBias namespace
namespace imuBias {
class ConstantBias : public DerivedValue<ConstantBias> {
class ConstantBias {
private:
Vector3 biasAcc_;
Vector3 biasGyro_;
@ -205,8 +205,7 @@ namespace imuBias {
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("imuBias::ConstantBias",
boost::serialization::base_object<Value>(*this));
ar & boost::serialization::make_nvp("imuBias::ConstantBias",*this);
ar & BOOST_SERIALIZATION_NVP(biasAcc_);
ar & BOOST_SERIALIZATION_NVP(biasGyro_);
}

View File

@ -51,7 +51,7 @@ public:
};
int TestValueData::ConstructorCount = 0;
int TestValueData::DestructorCount = 0;
class TestValue : public DerivedValue<TestValue> {
class TestValue {
TestValueData data_;
public:
virtual void print(const std::string& str = "") const {}

View File

@ -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<PoseRTV> {
class GTSAM_UNSTABLE_EXPORT PoseRTV {
protected:
Pose3 Rt_;

View File

@ -15,7 +15,7 @@
namespace gtsam {
class GTSAM_UNSTABLE_EXPORT BearingS2 : public DerivedValue<BearingS2> {
class GTSAM_UNSTABLE_EXPORT BearingS2 {
protected:
Rot2 azimuth_, elevation_;

View File

@ -22,7 +22,7 @@ namespace gtsam {
* @ingroup geometry
* \nosubgrouping
*/
class GTSAM_UNSTABLE_EXPORT Pose3Upright : public DerivedValue<Pose3Upright> {
class GTSAM_UNSTABLE_EXPORT Pose3Upright {
public:
static const size_t dimension = 4;