Fixed one unit test
parent
5e51745b86
commit
15ab2b27bc
|
|
@ -158,9 +158,9 @@ private:
|
|||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & boost::serialization::make_nvp("value", GenericValue<T>::value());
|
||||
// ar & boost::serialization::make_nvp("value",);
|
||||
// todo: implement a serialization for charts
|
||||
//ar & boost::serialization::make_nvp("Chart", boost::serialization::base_object<typename Chart>(*this));
|
||||
ar & boost::serialization::make_nvp("GenericValue", boost::serialization::base_object< GenericValue<T> >(*this));
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
|
|
|||
|
|
@ -56,7 +56,6 @@ public:
|
|||
virtual bool equals_(const Value& p, double tol = 1e-9) const {
|
||||
// Cast the base class Value pointer to a templated generic class pointer
|
||||
const GenericValue& genericValue2 = static_cast<const GenericValue&>(p);
|
||||
|
||||
// Return the result of using the equals traits for the derived class
|
||||
return traits::equals<T>(this->value_, genericValue2.value_, tol);
|
||||
}
|
||||
|
|
@ -69,7 +68,12 @@ public:
|
|||
virtual void print(const std::string& str) const {
|
||||
traits::print<T>(value_,str);
|
||||
}
|
||||
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Value);
|
||||
ar & BOOST_SERIALIZATION_NVP(value_);
|
||||
}
|
||||
protected:
|
||||
/// Assignment operator for this class not needed since GenricValue<T> is an abstract class
|
||||
|
||||
|
|
|
|||
|
|
@ -32,22 +32,37 @@ using namespace gtsam::serializationTestHelpers;
|
|||
|
||||
/* ************************************************************************* */
|
||||
// Export all classes derived from Value
|
||||
BOOST_CLASS_EXPORT(gtsam::Cal3_S2)
|
||||
BOOST_CLASS_EXPORT(gtsam::Cal3Bundler)
|
||||
BOOST_CLASS_EXPORT(gtsam::Point3)
|
||||
BOOST_CLASS_EXPORT(gtsam::Pose3)
|
||||
BOOST_CLASS_EXPORT(gtsam::Rot3)
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3_S2>)
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3DS2>)
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3Bundler>)
|
||||
BOOST_CLASS_EXPORT(gtsam::Cal3_S2);
|
||||
BOOST_CLASS_EXPORT(gtsam::Cal3Bundler);
|
||||
BOOST_CLASS_EXPORT(gtsam::Point3);
|
||||
BOOST_CLASS_EXPORT(gtsam::Pose3);
|
||||
BOOST_CLASS_EXPORT(gtsam::Rot3);
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3_S2>);
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3DS2>);
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3Bundler>);
|
||||
|
||||
namespace detail {
|
||||
template<class T> struct pack {
|
||||
typedef T type;
|
||||
};
|
||||
}
|
||||
#define CHART_VALUE_EXPORT(UNIQUE_NAME, TYPE) \
|
||||
typedef gtsam::ChartValue<TYPE,gtsam::DefaultChart<TYPE> > UNIQUE_NAME; \
|
||||
BOOST_CLASS_EXPORT( UNIQUE_NAME );
|
||||
|
||||
BOOST_CLASS_EXPORT(gtsam::ChartValue<gtsam::Pose3>);
|
||||
|
||||
/* ************************************************************************* */
|
||||
typedef PinholeCamera<Cal3_S2> PinholeCal3S2;
|
||||
typedef PinholeCamera<Cal3DS2> PinholeCal3DS2;
|
||||
typedef PinholeCamera<Cal3Bundler> PinholeCal3Bundler;
|
||||
|
||||
CHART_VALUE_EXPORT(gtsamPoint3Chart, gtsam::Point3);
|
||||
CHART_VALUE_EXPORT(Cal3S2Chart, PinholeCal3S2);
|
||||
CHART_VALUE_EXPORT(Cal3DS2Chart, PinholeCal3DS2);
|
||||
CHART_VALUE_EXPORT(Cal3BundlerChart, PinholeCal3Bundler);
|
||||
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
static Point3 pt3(1.0, 2.0, 3.0);
|
||||
static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
|
||||
|
|
|
|||
Loading…
Reference in New Issue