diff --git a/python/curves_python.cpp b/python/curves_python.cpp
index c8fe9c13ebd5b4d8f99a97e3d25d73307adc4f20..e255062d84986cd0bdd5bfcda59991ab0e1687f9 100644
--- a/python/curves_python.cpp
+++ b/python/curves_python.cpp
@@ -136,53 +136,42 @@ polynomial_t* wrapPolynomialConstructorFromBoundaryConditionsDegree3(const point
 }
 polynomial_t* wrapPolynomialConstructorFromBoundaryConditionsDegree5(const pointX_t& init, const pointX_t& d_init,
                                                                      const pointX_t& dd_init, const pointX_t& end,
-                                                                     const point_t& d_end, const point_t& dd_end,
+                                                                     const pointX_t& d_end, const pointX_t& dd_end,
                                                                      const real min, const real max) {
   return new polynomial_t(init, d_init, dd_init, end, d_end, dd_end, min, max);
 }
 /* End wrap polynomial */
 
 /* Wrap piecewise curve */
-piecewise_polynomial_curve_t* wrapPiecewisePolynomialCurveConstructor(const polynomial_t& pol) {
-  return new piecewise_polynomial_curve_t(pol);
+piecewise_t* wrapPiecewiseCurveConstructor(const curve_ptr_t& curve) {
+  return new piecewise_t(curve);
 }
-piecewise_polynomial_curve_t* wrapPiecewisePolynomialCurveEmptyConstructor() {
-  return new piecewise_polynomial_curve_t();
+piecewise_t* wrapPiecewisePolynomialCurveEmptyConstructor() {
+  return new piecewise_t();
 }
-piecewise_bezier_curve_t* wrapPiecewiseBezierCurveConstructor(const bezier_t& bc) {
-  return new piecewise_bezier_curve_t(bc);
+piecewise_SE3_t* wrapPiecewiseSE3Constructor(const curve_SE3_ptr_t& curve) {
+  return new piecewise_SE3_t(curve);
 }
-piecewise_bezier_linear_curve_t* wrapPiecewiseLinearBezierCurveConstructor(const bezier_linear_variable_t& bc) {
-  return new piecewise_bezier_linear_curve_t(bc);
-}
-piecewise_cubic_hermite_curve_t* wrapPiecewiseCubicHermiteCurveConstructor(const cubic_hermite_spline_t& ch) {
-  return new piecewise_cubic_hermite_curve_t(ch);
-}
-
-piecewise_SE3_curve_t* wrapPiecewiseSE3Constructor(const SE3Curve_t& curve) {
-  return new piecewise_SE3_curve_t(curve);
+piecewise_SE3_t* wrapPiecewiseSE3EmptyConstructor() {
+  return new piecewise_SE3_t();
 }
 
-piecewise_SE3_curve_t* wrapPiecewiseSE3EmptyConstructor() {
-  return new piecewise_SE3_curve_t();
-}
-static piecewise_polynomial_curve_t discretPointToPolynomialC0(const pointX_list_t& points,
+static piecewise_t discretPointToPolynomialC0(const pointX_list_t& points,
                                                                const time_waypoints_t& time_points) {
   t_pointX_t points_list = vectorFromEigenArray<pointX_list_t, t_pointX_t>(points);
   t_time_t time_points_list = vectorFromEigenVector<time_waypoints_t, t_time_t>(time_points);
-  return piecewise_polynomial_curve_t::convert_discrete_points_to_polynomial<polynomial_t>(points_list,
-                                                                                           time_points_list);
+  return piecewise_t::convert_discrete_points_to_polynomial<polynomial_t>(points_list,time_points_list);
 }
-static piecewise_polynomial_curve_t discretPointToPolynomialC1(const pointX_list_t& points,
+static piecewise_t discretPointToPolynomialC1(const pointX_list_t& points,
                                                                const pointX_list_t& points_derivative,
                                                                const time_waypoints_t& time_points) {
   t_pointX_t points_list = vectorFromEigenArray<pointX_list_t, t_pointX_t>(points);
   t_pointX_t points_derivative_list = vectorFromEigenArray<pointX_list_t, t_pointX_t>(points_derivative);
   t_time_t time_points_list = vectorFromEigenVector<time_waypoints_t, t_time_t>(time_points);
-  return piecewise_polynomial_curve_t::convert_discrete_points_to_polynomial<polynomial_t>(
+  return piecewise_t::convert_discrete_points_to_polynomial<polynomial_t>(
       points_list, points_derivative_list, time_points_list);
 }
-static piecewise_polynomial_curve_t discretPointToPolynomialC2(const pointX_list_t& points,
+static piecewise_t discretPointToPolynomialC2(const pointX_list_t& points,
                                                                const pointX_list_t& points_derivative,
                                                                const pointX_list_t& points_second_derivative,
                                                                const time_waypoints_t& time_points) {
@@ -191,20 +180,21 @@ static piecewise_polynomial_curve_t discretPointToPolynomialC2(const pointX_list
   t_pointX_t points_second_derivative_list = vectorFromEigenArray<pointX_list_t, t_pointX_t>(points_second_derivative);
 
   t_time_t time_points_list = vectorFromEigenVector<time_waypoints_t, t_time_t>(time_points);
-  return piecewise_polynomial_curve_t::convert_discrete_points_to_polynomial<polynomial_t>(
+  return piecewise_t::convert_discrete_points_to_polynomial<polynomial_t>(
       points_list, points_derivative_list, points_second_derivative_list, time_points_list);
 }
-void addFinalPointC0(piecewise_polynomial_curve_t& self, const pointX_t& end, const real time) {
+
+void addFinalPointC0(piecewise_t& self, const pointX_t& end, const real time) {
   if(self.num_curves() == 0)
     throw std::runtime_error("Piecewise append : you need to add at least one curve before using append(finalPoint) method.");
   if (self.is_continuous(1) && self.num_curves()>1 )
     std::cout << "Warning: by adding this final point to the piecewise curve, you loose C1 continuity and only "
                  "guarantee C0 continuity."
               << std::endl;
-  polynomial_t pol(self(self.max()), end, self.max(), time);
-  self.add_curve(pol);
+  curve_ptr_t pol(new polynomial_t(self(self.max()), end, self.max(), time));
+  self.add_curve_ptr(pol);
 }
-void addFinalPointC1(piecewise_polynomial_curve_t& self, const pointX_t& end, const pointX_t& d_end, const real time) {
+void addFinalPointC1(piecewise_t& self, const pointX_t& end, const pointX_t& d_end, const real time) {
   if(self.num_curves() == 0)
     throw std::runtime_error("Piecewise append : you need to add at least one curve before using append(finalPoint) method.");
   if (self.is_continuous(2) && self.num_curves()>1 )
@@ -212,10 +202,10 @@ void addFinalPointC1(piecewise_polynomial_curve_t& self, const pointX_t& end, co
                  "guarantee C1 continuity."
               << std::endl;
   if (!self.is_continuous(1)) std::cout << "Warning: the current piecewise curve is not C1 continuous." << std::endl;
-  polynomial_t pol(self(self.max()), self.derivate(self.max(), 1), end, d_end, self.max(), time);
-  self.add_curve(pol);
+  curve_ptr_t pol(new polynomial_t(self(self.max()), self.derivate(self.max(), 1), end, d_end, self.max(), time));
+  self.add_curve_ptr(pol);
 }
-void addFinalPointC2(piecewise_polynomial_curve_t& self, const pointX_t& end, const pointX_t& d_end,
+void addFinalPointC2(piecewise_t& self, const pointX_t& end, const pointX_t& d_end,
                      const pointX_t& dd_end, const real time) {
   if(self.num_curves() == 0)
     throw std::runtime_error("Piecewise append : you need to add at least one curve before using append(finalPoint) method.");
@@ -224,9 +214,9 @@ void addFinalPointC2(piecewise_polynomial_curve_t& self, const pointX_t& end, co
                  "guarantee C2 continuity."
               << std::endl;
   if (!self.is_continuous(2)) std::cout << "Warning: the current piecewise curve is not C2 continuous." << std::endl;
-  polynomial_t pol(self(self.max()), self.derivate(self.max(), 1), self.derivate(self.max(), 2), end, d_end, dd_end,
-                   self.max(), time);
-  self.add_curve(pol);
+  curve_ptr_t pol(new polynomial_t(self(self.max()), self.derivate(self.max(), 1), self.derivate(self.max(), 2), end, d_end, dd_end,
+                   self.max(), time));
+  self.add_curve_ptr(pol);
 }
 
 /* end wrap piecewise polynomial curve */
@@ -280,8 +270,8 @@ bezier_t* bezier_linear_variable_t_evaluate(const bezier_linear_variable_t* b, c
   return new bezier_t(evaluateLinear<bezier_t, bezier_linear_variable_t>(*b, x));
 }
 
-bezier_t::piecewise_bezier_curve_t (bezier_t::*splitspe)(const bezier_t::vector_x_t&) const = &bezier_t::split;
-bezier_linear_variable_t::piecewise_bezier_curve_t (bezier_linear_variable_t::*split_py)(
+bezier_t::piecewise_curve_t (bezier_t::*splitspe)(const bezier_t::vector_x_t&) const = &bezier_t::split;
+bezier_linear_variable_t::piecewise_curve_t (bezier_linear_variable_t::*split_py)(
     const bezier_linear_variable_t::vector_x_t&) const = &bezier_linear_variable_t::split;
 
 /* End wrap exact cubic spline */
@@ -359,13 +349,13 @@ pointX_t se3returnTranslation(const SE3Curve_t& curve, const real t) { return po
 typedef pinocchio::SE3Tpl<real, 0> SE3_t;
 typedef pinocchio::MotionTpl<real, 0> Motion_t;
 
-SE3_t piecewiseSE3ReturnPinocchio(const piecewise_SE3_curve_t& curve, const real t) { return SE3_t(curve(t).matrix()); }
+SE3_t piecewiseSE3ReturnPinocchio(const piecewise_SE3_t& curve, const real t) { return SE3_t(curve(t).matrix()); }
 
-Motion_t piecewiseSE3ReturnDerivatePinocchio(const piecewise_SE3_curve_t& curve, const real t, const std::size_t order) {
+Motion_t piecewiseSE3ReturnDerivatePinocchio(const piecewise_SE3_t& curve, const real t, const std::size_t order) {
   return Motion_t(curve.derivate(t, order));
 }
 
-void addFinalSE3(piecewise_SE3_curve_t& self, const SE3_t& end, const real time) {
+void addFinalSE3(piecewise_SE3_t& self, const SE3_t& end, const real time) {
   if(self.num_curves() == 0)
     throw std::runtime_error("Piecewise append : you need to add at least one curve before using append(finalPoint) method.");
   if (self.is_continuous(1) && self.num_curves()>1 )
@@ -378,14 +368,14 @@ void addFinalSE3(piecewise_SE3_curve_t& self, const SE3_t& end, const real time)
 
 #endif  // CURVES_WITH_PINOCCHIO_SUPPORT
 
-matrix4_t piecewiseSE3Return(const piecewise_SE3_curve_t& curve, const real t) { return curve(t).matrix(); }
+matrix4_t piecewiseSE3Return(const piecewise_SE3_t& curve, const real t) { return curve(t).matrix(); }
 
 
-matrix3_t piecewiseSE3returnRotation(const piecewise_SE3_curve_t& curve, const real t) { return curve(t).rotation(); }
+matrix3_t piecewiseSE3returnRotation(const piecewise_SE3_t& curve, const real t) { return curve(t).rotation(); }
 
-pointX_t piecewiseSE3returnTranslation(const piecewise_SE3_curve_t& curve, const real t) { return pointX_t(curve(t).translation()); }
+pointX_t piecewiseSE3returnTranslation(const piecewise_SE3_t& curve, const real t) { return pointX_t(curve(t).translation()); }
 
-void addFinalTransform(piecewise_SE3_curve_t& self, const matrix4_t& end, const real time) {
+void addFinalTransform(piecewise_SE3_t& self, const matrix4_t& end, const real time) {
   if(self.num_curves() == 0)
     throw std::runtime_error("Piecewise append : you need to add at least one curve before using append(finalPoint) method.");
   if (self.is_continuous(1) && self.num_curves()>1 )
@@ -406,7 +396,6 @@ BOOST_PYTHON_MODULE(curves) {
   eigenpy::enableEigenPySpecific<pointX_t, pointX_t>();
   eigenpy::enableEigenPySpecific<pointX_list_t, pointX_list_t>();
   eigenpy::enableEigenPySpecific<coeff_t, coeff_t>();
-  eigenpy::enableEigenPySpecific<point_list_t, point_list_t>();
   eigenpy::enableEigenPySpecific<matrix3_t, matrix3_t>();
   eigenpy::enableEigenPySpecific<matrix4_t, matrix4_t>();
   // eigenpy::enableEigenPySpecific<quaternion_t,quaternion_t>();
@@ -596,10 +585,10 @@ BOOST_PYTHON_MODULE(curves) {
 
   /** END polynomial function**/
   /** BEGIN piecewise curve function **/
-  class_<piecewise_polynomial_curve_t, bases<curve_abc_t> >("piecewise_polynomial_curve", init<>())
+  class_<piecewise_t, bases<curve_abc_t> >("piecewise", init<>())
       .def("__init__",
-           make_constructor(&wrapPiecewisePolynomialCurveConstructor, default_call_policies(), arg("curve")),
-           "Create a peicewise-polynomial curve containing the given polynomial curve.")
+           make_constructor(&wrapPiecewiseCurveConstructor, default_call_policies(), arg("curve")),
+           "Create a peicewise curve containing the given curve.")
       .def("FromPointsList", &discretPointToPolynomialC0,
            "Create a piecewise-polynomial connecting exactly all the given points at the given time. The created "
            "piecewise is C0 continuous.",
@@ -627,156 +616,80 @@ BOOST_PYTHON_MODULE(curves) {
            "and time and connecting exactly self(self.max()) and end. It guarantee C2 continuity and guarantee that "
            "self.derivate(time,1) == d_end and self.derivate(time,2) == dd_end",
            args("self", "end", "d_end", "d_end", "time"))
-      .def("compute_derivate", &piecewise_polynomial_curve_t::compute_derivate,
-           "Return a piecewise_polynomial curve which is the derivate of this.", args("self", "order"))
-      .def("append", &piecewise_polynomial_curve_t::add_curve,
+      .def("compute_derivate", &piecewise_t::compute_derivate,
+           "Return a piecewise curve which is the derivate of this.", args("self", "order"))
+      .def("append", &piecewise_t::add_curve_ptr,
            "Add a new curve to piecewise curve, which should be defined in T_{min},T_{max}] "
            "where T_{min} is equal toT_{max} of the actual piecewise curve.")
-      .def("is_continuous", &piecewise_polynomial_curve_t::is_continuous,
+      .def("is_continuous", &piecewise_t::is_continuous,
            "Check if the curve is continuous at the given order.",args("self,order"))
+      .def("convert_piecewise_curve_to_polynomial",
+           &piecewise_t::convert_piecewise_curve_to_bezier<polynomial_t>,
+           "Convert a piecewise curve to to a piecewise polynomial curve")
       .def("convert_piecewise_curve_to_bezier",
-           &piecewise_polynomial_curve_t::convert_piecewise_curve_to_bezier<bezier_t>,
-           "Convert a piecewise polynomial curve to to a piecewise bezier curve")
+           &piecewise_t::convert_piecewise_curve_to_bezier<bezier_t>,
+           "Convert a piecewise curve to to a piecewise bezier curve")
       .def("convert_piecewise_curve_to_cubic_hermite",
-           &piecewise_polynomial_curve_t::convert_piecewise_curve_to_cubic_hermite<cubic_hermite_spline_t>,
-           "Convert a piecewise polynomial curve to to a piecewise cubic hermite spline")
-      .def("curve_at_index", &piecewise_polynomial_curve_t::curve_at_index,
+           &piecewise_t::convert_piecewise_curve_to_cubic_hermite<cubic_hermite_spline_t>,
+           "Convert a piecewise curve to to a piecewise cubic hermite spline")
+      .def("curve_at_index", &piecewise_t::curve_at_index,
            return_value_policy<copy_const_reference>())
-      .def("curve_at_time", &piecewise_polynomial_curve_t::curve_at_time, return_value_policy<copy_const_reference>())
-      .def("num_curves", &piecewise_polynomial_curve_t::num_curves)
-      .def("saveAsText", &piecewise_polynomial_curve_t::saveAsText<piecewise_polynomial_curve_t>, bp::args("filename"),
-           "Saves *this inside a text file.")
-      .def("loadFromText", &piecewise_polynomial_curve_t::loadFromText<piecewise_polynomial_curve_t>,
-           bp::args("filename"), "Loads *this from a text file.")
-      .def("saveAsXML", &piecewise_polynomial_curve_t::saveAsXML<piecewise_polynomial_curve_t>,
-           bp::args("filename", "tag_name"), "Saves *this inside a XML file.")
-      .def("loadFromXML", &piecewise_polynomial_curve_t::loadFromXML<piecewise_polynomial_curve_t>,
-           bp::args("filename", "tag_name"), "Loads *this from a XML file.")
-      .def("saveAsBinary", &piecewise_polynomial_curve_t::saveAsBinary<piecewise_polynomial_curve_t>,
-           bp::args("filename"), "Saves *this inside a binary file.")
-      .def("loadFromBinary", &piecewise_polynomial_curve_t::loadFromBinary<piecewise_polynomial_curve_t>,
-           bp::args("filename"), "Loads *this from a binary file.");
-
-  class_<piecewise_bezier_curve_t, bases<curve_abc_t> >("piecewise_bezier_curve", init<>())
-      .def("__init__", make_constructor(&wrapPiecewiseBezierCurveConstructor))
-      .def("compute_derivate", &piecewise_polynomial_curve_t::compute_derivate,
-           "Return a piecewise_polynomial curve which is the derivate of this.", args("self", "order"))
-      .def("append", &piecewise_bezier_curve_t::add_curve)
-      .def("is_continuous", &piecewise_bezier_curve_t::is_continuous)
-      .def("convert_piecewise_curve_to_polynomial",
-           &piecewise_bezier_curve_t::convert_piecewise_curve_to_polynomial<polynomial_t>,
-           "Convert a piecewise bezier curve to to a piecewise polynomial curve")
-      .def("convert_piecewise_curve_to_cubic_hermite",
-           &piecewise_bezier_curve_t::convert_piecewise_curve_to_cubic_hermite<cubic_hermite_spline_t>,
-           "Convert a piecewise bezier curve to to a piecewise cubic hermite spline")
-      .def("curve_at_index", &piecewise_bezier_curve_t::curve_at_index, return_value_policy<copy_const_reference>())
-      .def("curve_at_time", &piecewise_bezier_curve_t::curve_at_time, return_value_policy<copy_const_reference>())
-      .def("num_curves", &piecewise_bezier_curve_t::num_curves)
-      .def("saveAsText", &piecewise_bezier_curve_t::saveAsText<piecewise_bezier_curve_t>, bp::args("filename"),
+      .def("curve_at_time", &piecewise_t::curve_at_time, return_value_policy<copy_const_reference>())
+      .def("num_curves", &piecewise_t::num_curves)
+      .def("saveAsText", &piecewise_t::saveAsText<piecewise_t>, bp::args("filename"),
            "Saves *this inside a text file.")
-      .def("loadFromText", &piecewise_bezier_curve_t::loadFromText<piecewise_bezier_curve_t>, bp::args("filename"),
-           "Loads *this from a text file.")
-      .def("saveAsXML", &piecewise_bezier_curve_t::saveAsXML<piecewise_bezier_curve_t>,
-           bp::args("filename", "tag_name"), "Saves *this inside a XML file.")
-      .def("loadFromXML", &piecewise_bezier_curve_t::loadFromXML<piecewise_bezier_curve_t>,
-           bp::args("filename", "tag_name"), "Loads *this from a XML file.")
-      .def("saveAsBinary", &piecewise_bezier_curve_t::saveAsBinary<piecewise_bezier_curve_t>, bp::args("filename"),
-           "Saves *this inside a binary file.")
-      .def("loadFromBinary", &piecewise_bezier_curve_t::loadFromBinary<piecewise_bezier_curve_t>, bp::args("filename"),
-           "Loads *this from a binary file.");
-
-  class_<piecewise_cubic_hermite_curve_t, bases<curve_abc_t> >("piecewise_cubic_hermite_curve", init<>())
-      .def("__init__", make_constructor(&wrapPiecewiseCubicHermiteCurveConstructor))
-      .def("append", &piecewise_cubic_hermite_curve_t::add_curve)
-      .def("is_continuous", &piecewise_cubic_hermite_curve_t::is_continuous)
-      .def("convert_piecewise_curve_to_polynomial",
-           &piecewise_cubic_hermite_curve_t::convert_piecewise_curve_to_polynomial<polynomial_t>,
-           "Convert a piecewise cubic hermite spline to to a piecewise polynomial curve")
-      .def("convert_piecewise_curve_to_bezier",
-           &piecewise_cubic_hermite_curve_t::convert_piecewise_curve_to_bezier<bezier_t>,
-           "Convert a piecewise cubic hermite spline to to a piecewise bezier curve")
-      .def("curve_at_index", &piecewise_cubic_hermite_curve_t::curve_at_index,
-           return_value_policy<copy_const_reference>())
-      .def("curve_at_time", &piecewise_cubic_hermite_curve_t::curve_at_time,
-           return_value_policy<copy_const_reference>())
-      .def("num_curves", &piecewise_cubic_hermite_curve_t::num_curves)
-      .def("saveAsText", &piecewise_cubic_hermite_curve_t::saveAsText<piecewise_cubic_hermite_curve_t>,
-           bp::args("filename"), "Saves *this inside a text file.")
-      .def("loadFromText", &piecewise_cubic_hermite_curve_t::loadFromText<piecewise_cubic_hermite_curve_t>,
+      .def("loadFromText", &piecewise_t::loadFromText<piecewise_t>,
            bp::args("filename"), "Loads *this from a text file.")
-      .def("saveAsXML", &piecewise_cubic_hermite_curve_t::saveAsXML<piecewise_cubic_hermite_curve_t>,
+      .def("saveAsXML", &piecewise_t::saveAsXML<piecewise_t>,
            bp::args("filename", "tag_name"), "Saves *this inside a XML file.")
-      .def("loadFromXML", &piecewise_cubic_hermite_curve_t::loadFromXML<piecewise_cubic_hermite_curve_t>,
+      .def("loadFromXML", &piecewise_t::loadFromXML<piecewise_t>,
            bp::args("filename", "tag_name"), "Loads *this from a XML file.")
-      .def("saveAsBinary", &piecewise_cubic_hermite_curve_t::saveAsBinary<piecewise_cubic_hermite_curve_t>,
+      .def("saveAsBinary", &piecewise_t::saveAsBinary<piecewise_t>,
            bp::args("filename"), "Saves *this inside a binary file.")
-      .def("loadFromBinary", &piecewise_cubic_hermite_curve_t::loadFromBinary<piecewise_cubic_hermite_curve_t>,
+      .def("loadFromBinary", &piecewise_t::loadFromBinary<piecewise_t>,
            bp::args("filename"), "Loads *this from a binary file.");
 
-  class_<piecewise_bezier_linear_curve_t, bases<curve_abc_t> >("piecewise_bezier_linear_curve_t", init<>())
-      .def("__init__", make_constructor(&wrapPiecewiseLinearBezierCurveConstructor))
-      .def("append", &piecewise_bezier_linear_curve_t::add_curve)
-      .def("is_continuous", &piecewise_bezier_linear_curve_t::is_continuous,
-           "Check if the curve is continuous at the given order.")
-      .def("curve_at_index", &piecewise_bezier_linear_curve_t::curve_at_index,
-           return_value_policy<copy_const_reference>())
-      .def("curve_at_time", &piecewise_bezier_linear_curve_t::curve_at_time,
-           return_value_policy<copy_const_reference>())
-      .def("num_curves", &piecewise_bezier_linear_curve_t::num_curves)
-      .def("saveAsText", &piecewise_bezier_linear_curve_t::saveAsText<piecewise_bezier_linear_curve_t>,
-           bp::args("filename"), "Saves *this inside a text file.")
-      .def("loadFromText", &piecewise_bezier_linear_curve_t::loadFromText<piecewise_bezier_linear_curve_t>,
-           bp::args("filename"), "Loads *this from a text file.")
-      .def("saveAsXML", &piecewise_bezier_linear_curve_t::saveAsXML<piecewise_bezier_linear_curve_t>,
-           bp::args("filename", "tag_name"), "Saves *this inside a XML file.")
-      .def("loadFromXML", &piecewise_bezier_linear_curve_t::loadFromXML<piecewise_bezier_linear_curve_t>,
-           bp::args("filename", "tag_name"), "Loads *this from a XML file.")
-      .def("saveAsBinary", &piecewise_bezier_linear_curve_t::saveAsBinary<piecewise_bezier_linear_curve_t>,
-           bp::args("filename"), "Saves *this inside a binary file.")
-      .def("loadFromBinary", &piecewise_bezier_linear_curve_t::loadFromBinary<piecewise_bezier_linear_curve_t>,
-           bp::args("filename"), "Loads *this from a binary file.");
-
-class_<piecewise_SE3_curve_t, bases<curve_abc_t> >("piecewise_SE3_curve", init<>())
+  class_<piecewise_SE3_t, bases<curve_abc_t> >("piecewise_SE3", init<>())
       .def("__init__", make_constructor(&wrapPiecewiseSE3Constructor, default_call_policies(), arg("curve")),
       "Create a piecewise-se3 curve containing the given se3 curve.")
       .def("__init__", make_constructor(&wrapPiecewiseSE3EmptyConstructor),
       "Create an empty piecewise-se3 curve.")
-//      .def("compute_derivate", &piecewise_SE3_curve_t::compute_derivate,
-//           "Return a piecewise_polynomial curve which is the derivate of this.", args("self", "order"))
-      .def("append", &piecewise_SE3_curve_t::add_curve,
+      .def("compute_derivate", &piecewise_SE3_t::compute_derivate,
+           "Return a piecewise_polynomial curve which is the derivate of this.", args("self", "order"))
+      .def("append", &piecewise_SE3_t::add_curve_ptr,
            "Add a new curve to piecewise curve, which should be defined in T_{min},T_{max}] "
            "where T_{min} is equal toT_{max} of the actual piecewise curve.",
            args("self,curve"))
-      .def("is_continuous", &piecewise_SE3_curve_t::is_continuous, "Check if the curve is continuous at the given order.",args("self,order"))
-      .def("curve_at_index", &piecewise_SE3_curve_t::curve_at_index, return_value_policy<copy_const_reference>())
-      .def("curve_at_time", &piecewise_SE3_curve_t::curve_at_time, return_value_policy<copy_const_reference>())
-      .def("num_curves", &piecewise_SE3_curve_t::num_curves)
+      .def("is_continuous", &piecewise_SE3_t::is_continuous, "Check if the curve is continuous at the given order.",args("self,order"))
+      .def("curve_at_index", &piecewise_SE3_t::curve_at_index, return_value_policy<copy_const_reference>())
+      .def("curve_at_time", &piecewise_SE3_t::curve_at_time, return_value_policy<copy_const_reference>())
+      .def("num_curves", &piecewise_SE3_t::num_curves)
       .def("rotation", &piecewiseSE3returnRotation, "Output the rotation (as a 3x3 matrix) at the given time.",
            args("self", "t"))
       .def("translation", &piecewiseSE3returnTranslation, "Output the translation (as a vector 3) at the given time.",
            args("self", "t"))
       .def("__call__", &piecewiseSE3Return, "Evaluate the curve at the given time. Return as an homogeneous matrix",
            args("self", "t"))
-      .def("derivate", &piecewise_SE3_curve_t::derivate,
+      .def("derivate", &piecewise_SE3_t::derivate,
            "Evaluate the derivative of order N of curve at time t. Return as a vector 6", args("self", "t", "N"))
-      .def("min", &piecewise_SE3_curve_t::min, "Get the LOWER bound on interval definition of the curve.")
-      .def("max", &piecewise_SE3_curve_t::max, "Get the HIGHER bound on interval definition of the curve.")
-      .def("dim", &piecewise_SE3_curve_t::dim, "Get the dimension of the curve.")
+      .def("min", &piecewise_SE3_t::min, "Get the LOWER bound on interval definition of the curve.")
+      .def("max", &piecewise_SE3_t::max, "Get the HIGHER bound on interval definition of the curve.")
+      .def("dim", &piecewise_SE3_t::dim, "Get the dimension of the curve.")
       .def("append", &addFinalTransform,
        "Append a new linear SE3 curve at the end of the piecewise curve, defined between self.max() "
        "and time and connecting exactly self(self.max()) and end",
        args("self", "end", "time"))
-      .def("saveAsText", &piecewise_SE3_curve_t::saveAsText<piecewise_SE3_curve_t>, bp::args("filename"),
+      .def("saveAsText", &piecewise_SE3_t::saveAsText<piecewise_SE3_t>, bp::args("filename"),
            "Saves *this inside a text file.")
-      .def("loadFromText", &piecewise_SE3_curve_t::loadFromText<piecewise_SE3_curve_t>, bp::args("filename"),
+      .def("loadFromText", &piecewise_SE3_t::loadFromText<piecewise_SE3_t>, bp::args("filename"),
            "Loads *this from a text file.")
-      .def("saveAsXML", &piecewise_SE3_curve_t::saveAsXML<piecewise_SE3_curve_t>,
+      .def("saveAsXML", &piecewise_SE3_t::saveAsXML<piecewise_SE3_t>,
            bp::args("filename", "tag_name"), "Saves *this inside a XML file.")
-      .def("loadFromXML", &piecewise_SE3_curve_t::loadFromXML<piecewise_SE3_curve_t>,
+      .def("loadFromXML", &piecewise_SE3_t::loadFromXML<piecewise_SE3_t>,
            bp::args("filename", "tag_name"), "Loads *this from a XML file.")
-      .def("saveAsBinary", &piecewise_SE3_curve_t::saveAsBinary<piecewise_SE3_curve_t>, bp::args("filename"),
+      .def("saveAsBinary", &piecewise_SE3_t::saveAsBinary<piecewise_SE3_t>, bp::args("filename"),
            "Saves *this inside a binary file.")
-      .def("loadFromBinary", &piecewise_SE3_curve_t::loadFromBinary<piecewise_SE3_curve_t>, bp::args("filename"),
+      .def("loadFromBinary", &piecewise_SE3_t::loadFromBinary<piecewise_SE3_t>, bp::args("filename"),
            "Loads *this from a binary file.")
         #ifdef CURVES_WITH_PINOCCHIO_SUPPORT
           .def("evaluateAsSE3", &piecewiseSE3ReturnPinocchio, "Evaluate the curve at the given time. Return as a pinocchio.SE3 object",
@@ -948,12 +861,9 @@ class_<piecewise_SE3_curve_t, bases<curve_abc_t> >("piecewise_SE3_curve", init<>
 
   /** END SE3 Curve**/
   /** BEGIN curves conversion**/
-  def("polynomial_from_bezier", polynomial_from_curve<polynomial_t, bezier_t>);
-  def("polynomial_from_hermite", polynomial_from_curve<polynomial_t, cubic_hermite_spline_t>);
-  def("bezier_from_hermite", bezier_from_curve<bezier_t, cubic_hermite_spline_t>);
-  def("bezier_from_polynomial", bezier_from_curve<bezier_t, polynomial_t>);
-  def("hermite_from_bezier", hermite_from_curve<cubic_hermite_spline_t, bezier_t>);
-  def("hermite_from_polynomial", hermite_from_curve<cubic_hermite_spline_t, polynomial_t>);
+  def("convert_to_polynomial", polynomial_from_curve<polynomial_t>);
+  def("convert_to_bezier", bezier_from_curve<bezier_t>);
+  def("convert_to_hermite", hermite_from_curve<cubic_hermite_spline_t>);
   /** END curves conversion**/
 
   optimization::python::exposeOptimization();