From ef610a94bbf138215244743a681738f1d890cf5c Mon Sep 17 00:00:00 2001 From: Guilhem Saurel <guilhem.saurel@laas.fr> Date: Thu, 5 Dec 2024 10:36:28 +0100 Subject: [PATCH] smart pointers: boost -> std --- include/ndcurves/bernstein.h | 2 +- include/ndcurves/bezier_curve.h | 2 +- include/ndcurves/curve_abc.h | 5 +- include/ndcurves/exact_cubic.h | 4 +- include/ndcurves/fwd.h | 12 +-- include/ndcurves/piecewise_curve.h | 8 +- include/ndcurves/se3_curve.h | 6 +- include/ndcurves/serialization/curves.hpp | 1 - python/ndcurves/curves_python.cpp | 62 +++++++-------- tests/Main.cpp | 91 ++++++++++++----------- 10 files changed, 97 insertions(+), 96 deletions(-) diff --git a/include/ndcurves/bernstein.h b/include/ndcurves/bernstein.h index c8fedaf..fcab1df 100644 --- a/include/ndcurves/bernstein.h +++ b/include/ndcurves/bernstein.h @@ -49,7 +49,7 @@ struct Bern { if (!(u >= 0. && u <= 1.)) { throw std::invalid_argument("u needs to be betwen 0 and 1."); } - return bin_m_i_ * (pow(u, i_))*pow((1 - u), m_minus_i); + return bin_m_i_ * (pow(u, i_)) * pow((1 - u), m_minus_i); } /// \brief Check if actual Bernstein polynomial and other are approximately diff --git a/include/ndcurves/bezier_curve.h b/include/ndcurves/bezier_curve.h index 921269b..d07ed7a 100644 --- a/include/ndcurves/bezier_curve.h +++ b/include/ndcurves/bezier_curve.h @@ -38,7 +38,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> { typedef std::vector<point_t, Eigen::aligned_allocator<point_t> > t_point_t; typedef typename t_point_t::const_iterator cit_point_t; typedef bezier_curve<Time, Numeric, Safe, Point> bezier_curve_t; - typedef boost::shared_ptr<bezier_curve_t> bezier_curve_ptr_t; + typedef std::shared_ptr<bezier_curve_t> bezier_curve_ptr_t; typedef piecewise_curve<Time, Numeric, Safe, point_t, point_t, bezier_curve_t> piecewise_curve_t; typedef curve_abc<Time, Numeric, Safe, point_t> curve_abc_t; // parent class diff --git a/include/ndcurves/curve_abc.h b/include/ndcurves/curve_abc.h index a0ab384..616e638 100644 --- a/include/ndcurves/curve_abc.h +++ b/include/ndcurves/curve_abc.h @@ -11,9 +11,8 @@ #ifndef _STRUCT_CURVE_ABC #define _STRUCT_CURVE_ABC -#include <boost/serialization/shared_ptr.hpp> -#include <boost/smart_ptr/shared_ptr.hpp> #include <functional> +#include <memory> #include "MathDefs.h" #include "serialization/archive.hpp" @@ -43,7 +42,7 @@ struct curve_abc : public serialization::Serializable { curve_t; // parent class typedef curve_abc<Time, Numeric, Safe, point_derivate_t> curve_derivate_t; // parent class - typedef boost::shared_ptr<curve_t> curve_ptr_t; + typedef std::shared_ptr<curve_t> curve_ptr_t; /* Constructors - destructors */ public: diff --git a/include/ndcurves/exact_cubic.h b/include/ndcurves/exact_cubic.h index e930213..ea04089 100644 --- a/include/ndcurves/exact_cubic.h +++ b/include/ndcurves/exact_cubic.h @@ -116,8 +116,8 @@ struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point> { std::size_t getNumberSplines() { return this->getNumberCurves(); } spline_t getSplineAt(std::size_t index) { - boost::shared_ptr<spline_t> s_ptr = - boost::dynamic_pointer_cast<spline_t>(this->curves_.at(index)); + std::shared_ptr<spline_t> s_ptr = + std::dynamic_pointer_cast<spline_t>(this->curves_.at(index)); if (s_ptr) return *s_ptr; else diff --git a/include/ndcurves/fwd.h b/include/ndcurves/fwd.h index fb4125e..e2921a4 100644 --- a/include/ndcurves/fwd.h +++ b/include/ndcurves/fwd.h @@ -10,7 +10,7 @@ #ifndef CURVES_FWD_H #define CURVES_FWD_H #include <Eigen/Dense> -#include <boost/smart_ptr/shared_ptr.hpp> +#include <memory> #include <vector> namespace ndcurves { @@ -94,11 +94,11 @@ typedef curve_abc<double, double, true, transform_t, point6_t> // (return dimension are fixed) // shared pointer to abstract types: -typedef boost::shared_ptr<curve_abc_t> curve_ptr_t; -typedef boost::shared_ptr<curve_3_t> curve3_ptr_t; -typedef boost::shared_ptr<curve_rotation_t> curve_rotation_ptr_t; -typedef boost::shared_ptr<curve_translation_t> curve_translation_ptr_t; -typedef boost::shared_ptr<curve_SE3_t> curve_SE3_ptr_t; +typedef std::shared_ptr<curve_abc_t> curve_ptr_t; +typedef std::shared_ptr<curve_3_t> curve3_ptr_t; +typedef std::shared_ptr<curve_rotation_t> curve_rotation_ptr_t; +typedef std::shared_ptr<curve_translation_t> curve_translation_ptr_t; +typedef std::shared_ptr<curve_SE3_t> curve_SE3_ptr_t; // definition of all curves class with pointX as return type: typedef polynomial<double, double, true, pointX_t, t_pointX_t> polynomial_t; diff --git a/include/ndcurves/piecewise_curve.h b/include/ndcurves/piecewise_curve.h index 42d130f..7c14f1a 100644 --- a/include/ndcurves/piecewise_curve.h +++ b/include/ndcurves/piecewise_curve.h @@ -9,8 +9,8 @@ #define _CLASS_PIECEWISE_CURVE #include <boost/serialization/vector.hpp> -#include <boost/smart_ptr/shared_ptr.hpp> #include <fstream> +#include <memory> #include <sstream> #include "curve_abc.h" @@ -46,7 +46,7 @@ struct piecewise_curve typedef curve_abc<Time, Numeric, Safe, point_t, point_derivate_t> base_curve_t; // parent class typedef CurveType curve_t; // contained curves base class - typedef boost::shared_ptr<curve_t> curve_ptr_t; + typedef std::shared_ptr<curve_t> curve_ptr_t; typedef typename std::vector<curve_ptr_t> t_curve_ptr_t; typedef typename std::vector<Time> t_time_t; typedef piecewise_curve<Time, Numeric, Safe, Point, Point_derivate, CurveType> @@ -54,7 +54,7 @@ struct piecewise_curve typedef piecewise_curve<Time, Numeric, Safe, Point_derivate, Point_derivate, typename CurveType::curve_derivate_t> piecewise_curve_derivate_t; - typedef boost::shared_ptr<typename piecewise_curve_derivate_t::curve_t> + typedef std::shared_ptr<typename piecewise_curve_derivate_t::curve_t> curve_derivate_ptr_t; public: @@ -174,7 +174,7 @@ struct piecewise_curve template <typename Curve> void add_curve(const Curve& curve) { - curve_ptr_t curve_ptr = boost::make_shared<Curve>(curve); + curve_ptr_t curve_ptr = std::make_shared<Curve>(curve); add_curve_ptr(curve_ptr); } diff --git a/include/ndcurves/se3_curve.h b/include/ndcurves/se3_curve.h index 363e020..847a63c 100644 --- a/include/ndcurves/se3_curve.h +++ b/include/ndcurves/se3_curve.h @@ -41,9 +41,9 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, 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 boost::shared_ptr<curve_translation_t> curve_translation_ptr_t; + typedef std::shared_ptr<curve_X_t> curve_ptr_t; + typedef std::shared_ptr<curve_rotation_t> curve_rotation_ptr_t; + typedef std::shared_ptr<curve_translation_t> curve_translation_ptr_t; typedef SO3Linear<Time, Numeric, Safe> SO3Linear_t; typedef polynomial<Time, Numeric, Safe, pointX_t> polynomial_t; diff --git a/include/ndcurves/serialization/curves.hpp b/include/ndcurves/serialization/curves.hpp index 416ab8c..445e753 100644 --- a/include/ndcurves/serialization/curves.hpp +++ b/include/ndcurves/serialization/curves.hpp @@ -12,7 +12,6 @@ */ #include <boost/serialization/shared_ptr.hpp> -#include <boost/shared_ptr.hpp> #include "ndcurves/bezier_curve.h" #include "ndcurves/constant_curve.h" diff --git a/python/ndcurves/curves_python.cpp b/python/ndcurves/curves_python.cpp index f6e5254..c06067c 100644 --- a/python/ndcurves/curves_python.cpp +++ b/python/ndcurves/curves_python.cpp @@ -749,10 +749,10 @@ SE3Curve_t* wrapSE3CurveFromPosAndRotation(const pointX_t& init_pos, SE3Curve_t* wrapSE3CurveFromBezier3Translation(bezier3_t& translation_curve, const matrix3_t& init_rot, const matrix3_t& end_rot) { - boost::shared_ptr<bezier3_t> translation( - new bezier3_t(translation_curve.waypoints().begin(), - translation_curve.waypoints().end(), - translation_curve.min(), translation_curve.max())); + std::shared_ptr<bezier3_t> translation = std::make_shared<bezier3_t>( + translation_curve.waypoints().begin(), + translation_curve.waypoints().end(), translation_curve.min(), + translation_curve.max()); return new SE3Curve_t(translation, init_rot, end_rot); } @@ -891,8 +891,8 @@ BOOST_PYTHON_MODULE(ndcurves) { eigenpy::exposeQuaternion();*/ /** END eigenpy init**/ /** Expose base abstracts class for each dimension/type : **/ - class_<curve_abc_t, boost::noncopyable, - boost::shared_ptr<curve_abc_callback>>("curve") + class_<curve_abc_t, boost::noncopyable, std::shared_ptr<curve_abc_callback>>( + "curve") .def("__call__", &curve_abc_t::operator(), "Evaluate the curve at the given time.", args("self", "t")) .def("derivate", &curve_abc_t::derivate, @@ -933,7 +933,7 @@ BOOST_PYTHON_MODULE(ndcurves) { .def_pickle(curve_pickle_suite<curve_abc_t>()); class_<curve_3_t, boost::noncopyable, bases<curve_abc_t>, - boost::shared_ptr<curve_3_callback>>("curve3") + std::shared_ptr<curve_3_callback>>("curve3") .def("__call__", &curve_3_t::operator(), "Evaluate the curve at the given time.", args("self", "t")) .def("derivate", &curve_3_t::derivate, @@ -959,7 +959,7 @@ BOOST_PYTHON_MODULE(ndcurves) { .def_pickle(curve_pickle_suite<curve_3_t>()); class_<curve_rotation_t, boost::noncopyable, bases<curve_abc_t>, - boost::shared_ptr<curve_rotation_callback>>("curve_rotation") + std::shared_ptr<curve_rotation_callback>>("curve_rotation") .def("__call__", &curve_rotation_t::operator(), "Evaluate the curve at the given time.", args("self", "t")) .def("derivate", &curve_rotation_t::derivate, @@ -985,7 +985,7 @@ BOOST_PYTHON_MODULE(ndcurves) { .def_pickle(curve_pickle_suite<curve_rotation_t>()); class_<curve_SE3_t, boost::noncopyable, bases<curve_abc_t>, - boost::shared_ptr<curve_SE3_callback>>("curve_SE3") + std::shared_ptr<curve_SE3_callback>>("curve_SE3") .def("__call__", &se3Return, "Evaluate the curve at the given time. Return as an homogeneous " "matrix.", @@ -1039,8 +1039,8 @@ BOOST_PYTHON_MODULE(ndcurves) { &bezier3_t::cross; bezier3_t (bezier3_t::*cross_pointBez3)(const bezier3_t::point_t&) const = &bezier3_t::cross; - class_<bezier3_t, bases<curve_3_t>, boost::shared_ptr<bezier3_t>>("bezier3", - init<>()) + class_<bezier3_t, bases<curve_3_t>, std::shared_ptr<bezier3_t>>("bezier3", + init<>()) .def("__init__", make_constructor(&wrapBezier3Constructor)) .def("__init__", make_constructor(&wrapBezier3ConstructorBounds)) .def("__init__", make_constructor(&wrapBezier3ConstructorConstraints)) @@ -1108,8 +1108,8 @@ BOOST_PYTHON_MODULE(ndcurves) { bezier_t (bezier_t::*cross_bez)(const bezier_t&) const = &bezier_t::cross; bezier_t (bezier_t::*cross_pointBez)(const bezier_t::point_t&) const = &bezier_t::cross; - class_<bezier_t, bases<curve_abc_t>, boost::shared_ptr<bezier_t>>("bezier", - init<>()) + class_<bezier_t, bases<curve_abc_t>, std::shared_ptr<bezier_t>>("bezier", + init<>()) .def("__init__", make_constructor(&wrapBezierConstructor)) .def("__init__", make_constructor(&wrapBezierConstructorBounds)) .def("__init__", make_constructor(&wrapBezierConstructorConstraints)) @@ -1204,8 +1204,8 @@ BOOST_PYTHON_MODULE(ndcurves) { const bezier_linear_variable_t::point_t&) const = &bezier_linear_variable_t::cross; class_<bezier_linear_variable_t, bases<curve_abc_t>, - boost::shared_ptr<bezier_linear_variable_t>>("bezier_linear_variable", - no_init) + std::shared_ptr<bezier_linear_variable_t>>("bezier_linear_variable", + no_init) .def("__init__", make_constructor(&wrapBezierLinearConstructor)) .def("__init__", make_constructor(&wrapBezierLinearConstructorBounds)) .def("min", &bezier_linear_variable_t::min) @@ -1269,7 +1269,7 @@ BOOST_PYTHON_MODULE(ndcurves) { polynomial_t (polynomial_t::*cross_point)(const polynomial_t::point_t&) const = &polynomial_t::cross; - class_<polynomial_t, bases<curve_abc_t>, boost::shared_ptr<polynomial_t>>( + class_<polynomial_t, bases<curve_abc_t>, std::shared_ptr<polynomial_t>>( "polynomial", init<>()) .def( "__init__", @@ -1360,7 +1360,7 @@ BOOST_PYTHON_MODULE(ndcurves) { /** END polynomial function**/ /** BEGIN piecewise curve function **/ - class_<piecewise_t, bases<curve_abc_t>, boost::shared_ptr<piecewise_t>>( + class_<piecewise_t, bases<curve_abc_t>, std::shared_ptr<piecewise_t>>( "piecewise", init<>()) .def("__init__", make_constructor(&wrapPiecewiseCurveConstructor, @@ -1438,7 +1438,7 @@ BOOST_PYTHON_MODULE(ndcurves) { .def(CopyableVisitor<piecewise_t>()) .def_pickle(curve_pickle_suite<piecewise_t>()); - class_<piecewise3_t, bases<curve_3_t>, boost::shared_ptr<piecewise3_t>>( + class_<piecewise3_t, bases<curve_3_t>, std::shared_ptr<piecewise3_t>>( "piecewise3", init<>()) .def("__init__", make_constructor(&wrapPiecewise3CurveConstructor, @@ -1513,7 +1513,7 @@ BOOST_PYTHON_MODULE(ndcurves) { .def_pickle(curve_pickle_suite<piecewise3_t>()); class_<piecewise_bezier_t, bases<curve_abc_t>, - boost::shared_ptr<piecewise_bezier_t>>("piecewise_bezier", init<>()) + std::shared_ptr<piecewise_bezier_t>>("piecewise_bezier", init<>()) .def("__init__", make_constructor(&wrapPiecewiseBezierConstructor, default_call_policies(), arg("curve")), @@ -1537,8 +1537,8 @@ BOOST_PYTHON_MODULE(ndcurves) { .def_pickle(curve_pickle_suite<piecewise_bezier_t>()); class_<piecewise_linear_bezier_t, bases<curve_abc_t>, - boost::shared_ptr<piecewise_linear_bezier_t>>( - "piecewise_bezier_linear", init<>(args("self"))) + std::shared_ptr<piecewise_linear_bezier_t>>("piecewise_bezier_linear", + init<>(args("self"))) .def("__init__", make_constructor(&wrapPiecewiseBezierLinearConstructor, default_call_policies(), arg("curve")), @@ -1562,8 +1562,8 @@ BOOST_PYTHON_MODULE(ndcurves) { .def(CopyableVisitor<piecewise_linear_bezier_t>()) .def_pickle(curve_pickle_suite<piecewise_linear_bezier_t>()); - class_<piecewise_SE3_t, bases<curve_SE3_t>, - boost::shared_ptr<piecewise_SE3_t>>("piecewise_SE3", init<>()) + class_<piecewise_SE3_t, bases<curve_SE3_t>, std::shared_ptr<piecewise_SE3_t>>( + "piecewise_SE3", init<>()) .def("__init__", make_constructor(&wrapPiecewiseSE3Constructor, default_call_policies(), arg("curve")), @@ -1602,7 +1602,7 @@ BOOST_PYTHON_MODULE(ndcurves) { /** END piecewise curve function **/ /** BEGIN exact_cubic curve**/ - class_<exact_cubic_t, bases<curve_abc_t>, boost::shared_ptr<exact_cubic_t>>( + class_<exact_cubic_t, bases<curve_abc_t>, std::shared_ptr<exact_cubic_t>>( "exact_cubic", init<>(args("self"))) .def("__init__", make_constructor(&wrapExactCubicConstructor, default_call_policies(), @@ -1622,8 +1622,8 @@ BOOST_PYTHON_MODULE(ndcurves) { /** END exact_cubic curve**/ /** BEGIN cubic_hermite_spline **/ class_<cubic_hermite_spline_t, bases<curve_abc_t>, - boost::shared_ptr<cubic_hermite_spline_t>>("cubic_hermite_spline", - init<>(args("self"))) + std::shared_ptr<cubic_hermite_spline_t>>("cubic_hermite_spline", + init<>(args("self"))) .def("__init__", make_constructor(&wrapCubicHermiteSplineConstructor, bp::default_call_policies(), args("points", "tangents", "times"))) @@ -1661,7 +1661,7 @@ BOOST_PYTHON_MODULE(ndcurves) { /** END bernstein polynomial**/ /** BEGIN SO3 Linear**/ - class_<SO3Linear_t, bases<curve_rotation_t>, boost::shared_ptr<SO3Linear_t>>( + class_<SO3Linear_t, bases<curve_rotation_t>, std::shared_ptr<SO3Linear_t>>( "SO3Linear", init<>()) .def("__init__", make_constructor( @@ -1689,7 +1689,7 @@ BOOST_PYTHON_MODULE(ndcurves) { /** END SO3 Linear**/ /** BEGIN SE3 Curve**/ - class_<SE3Curve_t, bases<curve_SE3_t>, boost::shared_ptr<SE3Curve_t>>( + class_<SE3Curve_t, bases<curve_SE3_t>, std::shared_ptr<SE3Curve_t>>( "SE3Curve", init<>()) .def("__init__", make_constructor( @@ -1763,7 +1763,7 @@ BOOST_PYTHON_MODULE(ndcurves) { /** END SE3 Curve**/ /** BEGIN constant curve function**/ - class_<constant_t, bases<curve_abc_t>, boost::shared_ptr<constant_t>>( + class_<constant_t, bases<curve_abc_t>, std::shared_ptr<constant_t>>( "constant", init<>()) .def("__init__", make_constructor(&wrapConstantConstructorTime, @@ -1785,7 +1785,7 @@ BOOST_PYTHON_MODULE(ndcurves) { .def_pickle(curve_pickle_suite<constant_t>()); /** END constant function**/ /** BEGIN constant 3 curve function**/ - class_<constant3_t, bases<curve_3_t>, boost::shared_ptr<constant3_t>>( + class_<constant3_t, bases<curve_3_t>, std::shared_ptr<constant3_t>>( "constant3", init<>()) .def("__init__", make_constructor(&wrapConstant3ConstructorTime, @@ -1807,7 +1807,7 @@ BOOST_PYTHON_MODULE(ndcurves) { .def_pickle(curve_pickle_suite<constant3_t>()); /** END constant 3 function**/ /** BEGIN sinusoidal curve function**/ - class_<sinusoidal_t, bases<curve_abc_t>, boost::shared_ptr<sinusoidal_t>>( + class_<sinusoidal_t, bases<curve_abc_t>, std::shared_ptr<sinusoidal_t>>( "sinusoidal", init<>()) .def("__init__", make_constructor(&wrapSinusoidalConstructor, default_call_policies(), diff --git a/tests/Main.cpp b/tests/Main.cpp index 0b66358..18812c3 100644 --- a/tests/Main.cpp +++ b/tests/Main.cpp @@ -1,7 +1,7 @@ -#include <boost/smart_ptr/shared_ptr.hpp> #include <cmath> #include <ctime> #include <iostream> +#include <memory> #include <string> #include "load_problem.h" @@ -1311,12 +1311,12 @@ void piecewiseCurveTest(bool& error) { vec2.push_back(b); // x=2, y=1, z=1 vec3.push_back(c); // x=3, y=1, z=1 // Create three polynomials of constant value in the interval of definition - boost::shared_ptr<polynomial_t> pol1_ptr( - new polynomial_t(vec1.begin(), vec1.end(), 0, 1)); - boost::shared_ptr<polynomial_t> pol2_ptr( - new polynomial_t(vec2.begin(), vec2.end(), 1, 2)); - boost::shared_ptr<polynomial_t> pol3_ptr( - new polynomial_t(vec3.begin(), vec3.end(), 2, 3)); + std::shared_ptr<polynomial_t> pol1_ptr = + std::make_shared<polynomial_t>(vec1.begin(), vec1.end(), 0, 1); + std::shared_ptr<polynomial_t> pol2_ptr = + std::make_shared<polynomial_t>(vec2.begin(), vec2.end(), 1, 2); + std::shared_ptr<polynomial_t> pol3_ptr = + std::make_shared<polynomial_t>(vec3.begin(), vec3.end(), 2, 3); // 1 polynomial in curve piecewise_t pc(pol1_ptr); res = pc(0.5); @@ -1355,10 +1355,10 @@ void piecewiseCurveTest(bool& error) { params1.push_back(c0); params1.push_back(b0); params1.push_back(a0); - boost::shared_ptr<bezier_t> bc0_ptr( - new bezier_t(params0.begin(), params0.end(), 0., 1.)); - boost::shared_ptr<bezier_t> bc1_ptr( - new bezier_t(params1.begin(), params1.end(), 1., 2.)); + std::shared_ptr<bezier_t> bc0_ptr = + std::make_shared<bezier_t>(params0.begin(), params0.end(), 0., 1.); + std::shared_ptr<bezier_t> bc1_ptr = + std::make_shared<bezier_t>(params1.begin(), params1.end(), 1., 2.); piecewise_t pc_C0(bc0_ptr); pc_C0.add_curve_ptr(bc1_ptr); // Check value in t=0.5 and t=1.5 @@ -1388,14 +1388,14 @@ void piecewiseCurveTest(bool& error) { time_control_points0.push_back(1.); // hermite 0 between [0,1] time_control_points1.push_back(1.); time_control_points1.push_back(3.); // hermite 1 between [1,3] - boost::shared_ptr<cubic_hermite_spline_t> chs0_ptr( - new cubic_hermite_spline_t(control_points_0.begin(), - control_points_0.end(), - time_control_points0)); - boost::shared_ptr<cubic_hermite_spline_t> chs1_ptr( - new cubic_hermite_spline_t(control_points_1.begin(), - control_points_1.end(), - time_control_points1)); + std::shared_ptr<cubic_hermite_spline_t> chs0_ptr = + std::make_shared<cubic_hermite_spline_t>(control_points_0.begin(), + control_points_0.end(), + time_control_points0); + std::shared_ptr<cubic_hermite_spline_t> chs1_ptr = + std::make_shared<cubic_hermite_spline_t>(control_points_1.begin(), + control_points_1.end(), + time_control_points1); piecewise_t pc_C1(chs0_ptr); pc_C1.add_curve_ptr(chs1_ptr); // Create piecewise curve C2 @@ -1408,10 +1408,10 @@ void piecewiseCurveTest(bool& error) { // in [1,2] vecb.push_back(b1); vecb.push_back(b1); // x=(t-1)+1, y=(t-1)+1, z=(t-1)+1 - boost::shared_ptr<polynomial_t> pola_ptr( - new polynomial_t(veca.begin(), veca.end(), 0, 1)); - boost::shared_ptr<polynomial_t> polb_ptr( - new polynomial_t(vecb.begin(), vecb.end(), 1, 2)); + std::shared_ptr<polynomial_t> pola_ptr = + std::make_shared<polynomial_t>(veca.begin(), veca.end(), 0, 1); + std::shared_ptr<polynomial_t> polb_ptr = + std::make_shared<polynomial_t>(vecb.begin(), vecb.end(), 1, 2); piecewise_t pc_C2(pola_ptr); pc_C2.add_curve_ptr(polb_ptr); // check C0 continuity @@ -2323,8 +2323,8 @@ void se3CurveTest(bool& error) { params.push_back(b); params.push_back(c); params.push_back(d); - boost::shared_ptr<bezier3_t> translation_bezier( - new bezier3_t(params.begin(), params.end(), min, max)); + std::shared_ptr<bezier3_t> translation_bezier = + std::make_shared<bezier3_t>(params.begin(), params.end(), min, max); cBezier = SE3Curve_t(translation_bezier, q0.toRotationMatrix(), q1.toRotationMatrix()); p0 = (*translation_bezier)(min); @@ -2522,8 +2522,8 @@ void Se3serializationTest(bool& error) { params.push_back(b); params.push_back(c); params.push_back(d); - boost::shared_ptr<bezier3_t> translation_bezier( - new bezier3_t(params.begin(), params.end(), min, max)); + std::shared_ptr<bezier3_t> translation_bezier = + std::make_shared<bezier3_t>(params.begin(), params.end(), min, max); cBezier = SE3Curve_t(translation_bezier, q0, q1); } @@ -3172,10 +3172,12 @@ void testOperatorEqual(bool& error) { // SE3 polynomial3_t pol3_0 = polynomial_from_curve<polynomial3_t>(bc3_0); - boost::shared_ptr<bezier3_t> translation_bezier(new bezier3_t(bc3_0)); - boost::shared_ptr<bezier3_t> translation_bezier2(new bezier3_t(bc3_0)); - boost::shared_ptr<polynomial3_t> translation_polynomial( - new polynomial3_t(pol3_0)); + std::shared_ptr<bezier3_t> translation_bezier = + std::make_shared<bezier3_t>(bc3_0); + std::shared_ptr<bezier3_t> translation_bezier2 = + std::make_shared<bezier3_t>(bc3_0); + std::shared_ptr<polynomial3_t> translation_polynomial = + std::make_shared<polynomial3_t>(pol3_0); SE3Curve_t se3_bezier1 = SE3Curve_t(translation_bezier, q0.toRotationMatrix(), q1.toRotationMatrix()); SE3Curve_t se3_bezier12 = SE3Curve_t( @@ -3185,8 +3187,8 @@ void testOperatorEqual(bool& error) { SE3Curve_t se3_bezier2(se3_bezier1); SE3Curve_t se3_bezier3 = SE3Curve_t(translation_bezier, q0.toRotationMatrix(), q2.toRotationMatrix()); - boost::shared_ptr<polynomial3_t> translation_polynomial2( - new polynomial3_t(pol3_2)); + std::shared_ptr<polynomial3_t> translation_polynomial2 = + std::make_shared<polynomial3_t>(pol3_2); SE3Curve_t se3_pol2 = SE3Curve_t( translation_polynomial2, q0.toRotationMatrix(), q1.toRotationMatrix()); // std::cout<<"Should call se3 method : "<<std::endl; @@ -3240,10 +3242,10 @@ void testOperatorEqual(bool& error) { params1.push_back(c0); params1.push_back(b0); params1.push_back(a0); - boost::shared_ptr<bezier_t> bc0_ptr( - new bezier_t(params0.begin(), params0.end(), 0., 1.)); - boost::shared_ptr<bezier_t> bc1_ptr( - new bezier_t(params1.begin(), params1.end(), 1., 2.)); + std::shared_ptr<bezier_t> bc0_ptr = + std::make_shared<bezier_t>(params0.begin(), params0.end(), 0., 1.); + std::shared_ptr<bezier_t> bc1_ptr = + std::make_shared<bezier_t>(params1.begin(), params1.end(), 1., 2.); piecewise_t pc_C0(bc0_ptr); pc_C0.add_curve_ptr(bc1_ptr); piecewise_t pc_C1(bc0_ptr); @@ -3251,8 +3253,8 @@ void testOperatorEqual(bool& error) { piecewise_t pc_C2(pc_C0); piecewise_t pc_C3(bc0_ptr); piecewise_t pc_C4(bc0_ptr); - boost::shared_ptr<bezier_t> bc2_ptr( - new bezier_t(params0.begin(), params0.end(), 1., 2.)); + std::shared_ptr<bezier_t> bc2_ptr = + std::make_shared<bezier_t>(params0.begin(), params0.end(), 1., 2.); pc_C4.add_curve_ptr(bc2_ptr); // std::cout<<"Should call piecewise method -> bezier , bezier: "<<std::endl; if (pc_C0 != pc_C1) { @@ -3297,16 +3299,17 @@ void testOperatorEqual(bool& error) { translation_polynomial->derivate(translation_polynomial->max(), 1)); point3_t p_end_se3(1, -2, 6); point3_t dp_end_se3(3.5, 2.5, -9); - boost::shared_ptr<polynomial3_t> translation_pol3(new polynomial3_t( - p_init_se3, dp_init_se3, p_end_se3, dp_end_se3, - translation_polynomial->max(), translation_polynomial->max() + 2.5)); + std::shared_ptr<polynomial3_t> translation_pol3 = + std::make_shared<polynomial3_t>(p_init_se3, dp_init_se3, p_end_se3, + dp_end_se3, translation_polynomial->max(), + translation_polynomial->max() + 2.5); curve_SE3_ptr_t se3_pol_3(new SE3Curve_t( translation_pol3, q1.toRotationMatrix(), q2.toRotationMatrix())); pc_se3_1.add_curve_ptr(se3_pol_3); piecewise_SE3_t pc_se3_2(pc_se3_1); - piecewise_SE3_t pc_se3_3(boost::make_shared<SE3Curve_t>(se3_pol1)); + piecewise_SE3_t pc_se3_3(std::make_shared<SE3Curve_t>(se3_pol1)); pc_se3_3.add_curve_ptr(se3_pol_3); - piecewise_SE3_t pc_se3_4(boost::make_shared<SE3Curve_t>(se3_pol2)); + piecewise_SE3_t pc_se3_4(std::make_shared<SE3Curve_t>(se3_pol2)); pc_se3_4.add_curve_ptr(se3_pol_3); // std::cout<<"Should call piecewise method -> SE3 , SE3: "<<std::endl; if (pc_se3_1 != pc_se3_2) { -- GitLab