From 6e736bb53e993c53eb7d3a78433550cef6061c43 Mon Sep 17 00:00:00 2001
From: Pierre Fernbach <pierre.fernbach@laas.fr>
Date: Wed, 27 Nov 2019 11:13:28 +0100
Subject: [PATCH] add BOOST_SERIALIZATION_BASE_OBJECT_NVP to the serialization
 method of all child class of curve_abc

---
 include/curves/bezier_curve.h         | 2 ++
 include/curves/cubic_hermite_spline.h | 6 +++++-
 include/curves/exact_cubic.h          | 1 +
 include/curves/piecewise_curve.h      | 3 +++
 include/curves/polynomial.h           | 1 +
 include/curves/so3_linear.h           | 6 +++++-
 6 files changed, 17 insertions(+), 2 deletions(-)

diff --git a/include/curves/bezier_curve.h b/include/curves/bezier_curve.h
index c0f9cfb..36eb7e1 100644
--- a/include/curves/bezier_curve.h
+++ b/include/curves/bezier_curve.h
@@ -40,6 +40,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> {
   typedef typename t_point_t::const_iterator cit_point_t;
   typedef bezier_curve<Time, Numeric, Safe, Point> bezier_curve_t;
   typedef piecewise_curve<Time, Numeric, Safe, point_t, t_point_t, bezier_curve_t> piecewise_bezier_curve_t;
+  typedef curve_abc<Time, Numeric, Safe, point_t> curve_abc_t;  // parent class
 
   /* Constructors - destructors */
  public:
@@ -444,6 +445,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> {
     if (version) {
       // Do something depending on version ?
     }
+    ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
     ar& boost::serialization::make_nvp("dim", dim_);
     ar& boost::serialization::make_nvp("T_min", T_min_);
     ar& boost::serialization::make_nvp("T_max", T_max_);
diff --git a/include/curves/cubic_hermite_spline.h b/include/curves/cubic_hermite_spline.h
index 52c9571..79a7a9b 100644
--- a/include/curves/cubic_hermite_spline.h
+++ b/include/curves/cubic_hermite_spline.h
@@ -33,10 +33,13 @@ namespace curves {
 template <typename Time = double, typename Numeric = Time, bool Safe = false,
           typename Point = Eigen::Matrix<Numeric, Eigen::Dynamic, 1> >
 struct cubic_hermite_spline : public curve_abc<Time, Numeric, Safe, Point> {
+  typedef Point point_t;
   typedef std::pair<Point, Point> pair_point_tangent_t;
   typedef std::vector<pair_point_tangent_t, Eigen::aligned_allocator<Point> > t_pair_point_tangent_t;
   typedef std::vector<Time> vector_time_t;
   typedef Numeric num_t;
+  typedef curve_abc<Time, Numeric, Safe, point_t> curve_abc_t;  // parent class
+
 
  public:
   /// \brief Empty constructor. Curve obtained this way can not perform other class functions.
@@ -356,6 +359,7 @@ struct cubic_hermite_spline : public curve_abc<Time, Numeric, Safe, Point> {
     if (version) {
       // Do something depending on version ?
     }
+    ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
     ar& boost::serialization::make_nvp("dim", dim_);
     ar& boost::serialization::make_nvp("control_points", control_points_);
     ar& boost::serialization::make_nvp("time_control_points", time_control_points_);
@@ -367,4 +371,4 @@ struct cubic_hermite_spline : public curve_abc<Time, Numeric, Safe, Point> {
   }
 };  // End struct Cubic hermite spline
 }  // namespace curves
-#endif  //_CLASS_CUBICHERMITESPLINE
\ No newline at end of file
+#endif  //_CLASS_CUBICHERMITESPLINE
diff --git a/include/curves/exact_cubic.h b/include/curves/exact_cubic.h
index 6d748cc..4991067 100644
--- a/include/curves/exact_cubic.h
+++ b/include/curves/exact_cubic.h
@@ -54,6 +54,7 @@ struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point, T_Point,
 
   typedef exact_cubic<Time, Numeric, Safe, Point, T_Point, SplineBase> exact_cubic_t;
   typedef piecewise_curve<Time, Numeric, Safe, Point, T_Point, SplineBase> piecewise_curve_t;
+  typedef curve_abc<Time, Numeric, Safe, point_t> curve_abc_t;  // parent class
 
   /* Constructors - destructors */
  public:
diff --git a/include/curves/piecewise_curve.h b/include/curves/piecewise_curve.h
index 1557385..c6b75d9 100644
--- a/include/curves/piecewise_curve.h
+++ b/include/curves/piecewise_curve.h
@@ -35,6 +35,8 @@ struct piecewise_curve : public curve_abc<Time, Numeric, Safe, Point,Point_deriv
   typedef Curve curve_t;
   typedef typename std::vector<curve_t> t_curve_t;
   typedef typename std::vector<Time> t_time_t;
+  typedef curve_abc<Time, Numeric, Safe, point_t,point_derivate_t> curve_abc_t;  // parent class
+
 
  public:
   /// \brief Empty constructor. Add at least one curve to call other class functions.
@@ -380,6 +382,7 @@ struct piecewise_curve : public curve_abc<Time, Numeric, Safe, Point,Point_deriv
     if (version) {
       // Do something depending on version ?
     }
+    ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
     ar& boost::serialization::make_nvp("dim", dim_);
     ar& boost::serialization::make_nvp("curves", curves_);
     ar& boost::serialization::make_nvp("time_curves", time_curves_);
diff --git a/include/curves/polynomial.h b/include/curves/polynomial.h
index 144c510..757c13c 100644
--- a/include/curves/polynomial.h
+++ b/include/curves/polynomial.h
@@ -359,6 +359,7 @@ struct polynomial : public curve_abc<Time, Numeric, Safe, Point> {
     if (version) {
       // Do something depending on version ?
     }
+    ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
     ar& boost::serialization::make_nvp("dim", dim_);
     ar& boost::serialization::make_nvp("coefficients", coefficients_);
     ar& boost::serialization::make_nvp("dim", dim_);
diff --git a/include/curves/so3_linear.h b/include/curves/so3_linear.h
index 76c0223..bd8ecee 100644
--- a/include/curves/so3_linear.h
+++ b/include/curves/so3_linear.h
@@ -22,9 +22,11 @@ struct SO3Linear : public curve_abc<Time, Numeric, Safe, Eigen::Matrix<Numeric,
   typedef Numeric Scalar;
   typedef Eigen::Matrix<Scalar, 3, 1> point3_t;
   typedef Eigen::Matrix<Scalar, 3, 3> matrix3_t;
+  typedef matrix3_t point_t;
+  typedef point3_t point_derivate_t;
   typedef Eigen::Quaternion<Scalar> quaternion_t;
   typedef Time time_t;
-  typedef curve_abc<Time, Numeric, Safe, matrix3_t, point3_t> curve_abc_t;
+  typedef curve_abc<Time, Numeric, Safe, point_t, point_derivate_t> curve_abc_t;
   typedef SO3Linear<Time, Numeric, Safe> SO3Linear_t;
 
  public:
@@ -155,6 +157,7 @@ struct SO3Linear : public curve_abc<Time, Numeric, Safe, Eigen::Matrix<Numeric,
     if (version) {
       // Do something depending on version ?
     }
+    ar>> BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
     ar>> boost::serialization::make_nvp("dim", dim_);
     matrix3_t init,end;
     ar >> boost::serialization::make_nvp("init_rotation", init);
@@ -172,6 +175,7 @@ struct SO3Linear : public curve_abc<Time, Numeric, Safe, Eigen::Matrix<Numeric,
     if (version) {
       // Do something depending on version ?
     }
+    ar<< BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
     ar<< boost::serialization::make_nvp("dim", dim_);
     matrix3_t init_matrix(getInitRotation());
     matrix3_t end_matrix(getEndRotation());
-- 
GitLab