diff --git a/include/curves/se3_curve.h b/include/curves/se3_curve.h
index 98ebf36c803fe16c7d5eb249c81a780286b99954..c65ebc3776ced2809eb135747f39407d0ea28226 100644
--- a/include/curves/se3_curve.h
+++ b/include/curves/se3_curve.h
@@ -32,8 +32,10 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
   typedef Time time_t;
   typedef curve_abc<Time, Numeric, Safe, point_t, point_derivate_t> curve_abc_t;  // parent class
   typedef curve_abc<Time, Numeric, Safe, pointX_t> curve_X_t;                     // generic class of curve
-  typedef curve_abc<Time, Numeric, Safe, matrix3_t, point3_t>
-      curve_rotation_t;  // templated class used for the rotation (return dimension are fixed)
+  typedef curve_abc<Time, Numeric, Safe, matrix3_t, point3_t> curve_rotation_t;  // templated class used for the rotation (return dimension are fixed)
+  typedef boost::shared_ptr<curve_X_t> curve_ptr_t;
+  typedef boost::shared_ptr<curve_rotation_t> curve_rotation_ptr_t;
+
   typedef SO3Linear<Time, Numeric, Safe> SO3Linear_t;
   typedef polynomial<Time, Numeric, Safe, pointX_t> polynomial_t;
   typedef SE3Curve<Time, Numeric, Safe> SE3Curve_t;
@@ -42,7 +44,7 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
   /* Constructors - destructors */
   /// \brief Empty constructor. Curve obtained this way can not perform other class functions.
   ///
-  SE3Curve() : curve_abc_t(), dim_(3), translation_curve_(NULL), rotation_curve_(NULL), T_min_(0), T_max_(0) {}
+  SE3Curve() : curve_abc_t(), dim_(3), translation_curve_(), rotation_curve_(), T_min_(0), T_max_(0) {}
 
   /// \brief Destructor
   ~SE3Curve() {
@@ -93,7 +95,7 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
   /* Constructor with curve object for the translation : */
   /// \brief Constructor from curve for the translation and init/end rotation, with quaternion.
   /// Use SO3Linear for rotation with the same time bounds as the
-  SE3Curve(curve_X_t* translation_curve, const Quaternion& init_rot, const Quaternion& end_rot)
+  SE3Curve(curve_ptr_t translation_curve, const Quaternion& init_rot, const Quaternion& end_rot)
       : curve_abc_t(),
         dim_(6),
         translation_curve_(translation_curve),
@@ -104,7 +106,7 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
   }
   /// \brief Constructor from curve for the translation and init/end rotation, with rotation matrix.
   /// Use SO3Linear for rotation with the same time bounds as the
-  SE3Curve(curve_X_t* translation_curve, const matrix3_t& init_rot, const matrix3_t& end_rot)
+  SE3Curve(curve_ptr_t translation_curve, const matrix3_t& init_rot, const matrix3_t& end_rot)
       : curve_abc_t(),
         dim_(6),
         translation_curve_(translation_curve),
@@ -116,7 +118,7 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
 
   /* Constructor from translation and rotation curves object : */
   /// \brief Constructor from from translation and rotation curves object
-  SE3Curve(curve_X_t* translation_curve, curve_rotation_t* rotation_curve)
+  SE3Curve(curve_ptr_t translation_curve, curve_rotation_ptr_t rotation_curve)
       : curve_abc_t(),
         dim_(6),
         translation_curve_(translation_curve),
@@ -176,8 +178,8 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
 
   /*Attributes*/
   std::size_t dim_;  // dim doesn't mean anything in this class ...
-  curve_X_t* translation_curve_ = NULL;
-  curve_rotation_t* rotation_curve_ = NULL;
+  curve_ptr_t translation_curve_;
+  curve_rotation_ptr_t rotation_curve_;
   time_t T_min_, T_max_;
   /*Attributes*/
 
diff --git a/python/curves_python.cpp b/python/curves_python.cpp
index 2c10e78ac1705982a67f96af66e50adc16277b2d..c920a7f68b670951bbc0a6320c2451d0c8739713 100644
--- a/python/curves_python.cpp
+++ b/python/curves_python.cpp
@@ -311,18 +311,18 @@ SE3Curve_t* wrapSE3CurveFromPosAndRotation(const pointX_t& init_pos, const point
 
 SE3Curve_t* wrapSE3CurveFromBezier3Translation(bezier3_t& translation_curve, const matrix3_t& init_rot,
                                                const matrix3_t& end_rot) {
-  bezier_t* translation = new bezier_t(translation_curve.waypoints().begin(), translation_curve.waypoints().end(),
-                                       translation_curve.min(), translation_curve.max());
+  boost::shared_ptr<bezier_t> translation(new bezier_t(translation_curve.waypoints().begin(), translation_curve.waypoints().end(),
+                                       translation_curve.min(), translation_curve.max()));
   return new SE3Curve_t(translation, init_rot, end_rot);
 }
 
-SE3Curve_t* wrapSE3CurveFromTranslation(curve_abc_t& translation_curve, const matrix3_t& init_rot,
+SE3Curve_t* wrapSE3CurveFromTranslation(const curve_ptr_t& translation_curve, const matrix3_t& init_rot,
                                         const matrix3_t& end_rot) {
-  return new SE3Curve_t(&translation_curve, init_rot, end_rot);
+  return new SE3Curve_t(translation_curve, init_rot, end_rot);
 }
 
-SE3Curve_t* wrapSE3CurveFromTwoCurves(curve_abc_t& translation_curve, curve_rotation_t& rotation_curve) {
-  return new SE3Curve_t(&translation_curve, &rotation_curve);
+SE3Curve_t* wrapSE3CurveFromTwoCurves(const curve_ptr_t& translation_curve,const curve_rotation_ptr_t& rotation_curve) {
+  return new SE3Curve_t(translation_curve,rotation_curve);
 }
 
 #ifdef CURVES_WITH_PINOCCHIO_SUPPORT
diff --git a/python/python_variables.h b/python/python_variables.h
index bc380f7abdd4878f411e5941ec615dd1ad9da6b1..70ebfcbe6bcf94ef3e830dde7950262e60a188d3 100644
--- a/python/python_variables.h
+++ b/python/python_variables.h
@@ -83,6 +83,8 @@ typedef curve_abc<real, real, true, pointX_t> curve_abc_t;  // generic class of
 typedef curve_abc<real, real, true, point3_t> curve_3_t;    // generic class of curve of size 3
 typedef curve_abc<real, real, true, matrix3_t, point3_t>
     curve_rotation_t;  // templated class used for the rotation (return dimension are fixed)
+typedef boost::shared_ptr<curve_abc_t> curve_ptr_t;
+typedef boost::shared_ptr<curve_rotation_t> curve_rotation_ptr_t;
 typedef curves::cubic_hermite_spline<real, real, true, pointX_t> cubic_hermite_spline_t;
 typedef curves::bezier_curve<real, real, true, pointX_t> bezier_t;
 typedef curves::bezier_curve<real, real, true, Eigen::Vector3d> bezier3_t;
diff --git a/tests/Main.cpp b/tests/Main.cpp
index 14922b8cca7dfbb3e482588af010f83d83100c73..3ec5e719450ae9bb10bd0a1730371e904ca49c9b 100644
--- a/tests/Main.cpp
+++ b/tests/Main.cpp
@@ -1769,7 +1769,7 @@ void se3CurveTest(bool& error) {
     params.push_back(b);
     params.push_back(c);
     params.push_back(d);
-    bezier_curve_t* translation_bezier = new bezier_curve_t(params.begin(), params.end(), min, max);
+    boost::shared_ptr<bezier_curve_t> translation_bezier(new bezier_curve_t(params.begin(), params.end(), min, max));
     cBezier = SE3Curve_t(translation_bezier, q0.toRotationMatrix(), q1.toRotationMatrix());
     p0 = (*translation_bezier)(min);
     p1 = (*translation_bezier)(max);