From 0051a8f2ff8de4908fe12353ca8ec8fe54ccaffc Mon Sep 17 00:00:00 2001 From: pFernbach <pierre.fernbach@gmail.com> Date: Wed, 15 Jan 2020 16:03:56 +0100 Subject: [PATCH] [C++] refactor hpp-spline -> curves --- include/hpp/bezier-com-traj/common_solve_methods.hh | 2 +- include/hpp/bezier-com-traj/data.hh | 6 +++--- include/hpp/bezier-com-traj/definitions.hh | 8 ++++---- include/hpp/bezier-com-traj/utils.hh | 2 +- src/common_solve_methods.cpp | 2 +- src/computeCOMTraj.cpp | 4 ++-- src/solve_0_step.cpp | 6 +++--- src/utils.cpp | 6 +++--- tests/test-bezier-symbolic.cpp | 2 +- 9 files changed, 19 insertions(+), 19 deletions(-) diff --git a/include/hpp/bezier-com-traj/common_solve_methods.hh b/include/hpp/bezier-com-traj/common_solve_methods.hh index 7d6bf24..6f073e8 100644 --- a/include/hpp/bezier-com-traj/common_solve_methods.hh +++ b/include/hpp/bezier-com-traj/common_solve_methods.hh @@ -24,7 +24,7 @@ namespace bezier_com_traj { * @return a vector of waypoint representing the discretization of the curve */ BEZIER_COM_TRAJ_DLLAPI std::vector<waypoint6_t> ComputeDiscretizedWaypoints( - const std::vector<waypoint6_t>& wps, const std::vector<spline::Bern<double> >& bernstein, int numSteps); + const std::vector<waypoint6_t>& wps, const std::vector<curves::Bern<double> >& bernstein, int numSteps); /** * @brief compute6dControlPointInequalities Given linear and angular control waypoints, diff --git a/include/hpp/bezier-com-traj/data.hh b/include/hpp/bezier-com-traj/data.hh index 12b1363..72f2caf 100644 --- a/include/hpp/bezier-com-traj/data.hh +++ b/include/hpp/bezier-com-traj/data.hh @@ -11,7 +11,7 @@ #include <hpp/bezier-com-traj/definitions.hh> #include <hpp/bezier-com-traj/utils.hh> #include <hpp/bezier-com-traj/solver/solver-abstract.hpp> -#include <hpp/spline/bezier_curve.h> +#include <curves/bezier_curve.h> #include <hpp/centroidal-dynamics/centroidal_dynamics.hh> #include <Eigen/Dense> @@ -117,8 +117,8 @@ typedef solvers::ResultData ResultData; struct BEZIER_COM_TRAJ_DLLAPI ResultDataCOMTraj : public ResultData { ResultDataCOMTraj() : ResultData(), - c_of_t_(bezier_t::zero()), - dL_of_t_(bezier_t::zero()), + c_of_t_(bezier_t::zero(3)), + dL_of_t_(bezier_t::zero(3)), dc1_(point_t::Zero()), ddc1_(point_t::Zero()) {} ~ResultDataCOMTraj() {} diff --git a/include/hpp/bezier-com-traj/definitions.hh b/include/hpp/bezier-com-traj/definitions.hh index 4d68b1d..37a0bab 100644 --- a/include/hpp/bezier-com-traj/definitions.hh +++ b/include/hpp/bezier-com-traj/definitions.hh @@ -7,7 +7,7 @@ #define BEZIER_COM_TRAJ_DEFINITIONS_H #include <hpp/centroidal-dynamics/centroidal_dynamics.hh> -#include <hpp/spline/bezier_curve.h> +#include <curves/bezier_curve.h> #include <Eigen/Dense> namespace bezier_com_traj { @@ -51,9 +51,9 @@ typedef std::pair<matrix3_t, point3_t> waypoint3_t; typedef std::pair<Matrix39, point3_t> waypoint9_t; struct waypoint_t; // forward declaration -typedef spline::bezier_curve<double, double, 3, true, point_t> bezier_t; -typedef spline::bezier_curve<double, double, 3, true, waypoint_t> bezier_wp_t; -typedef spline::bezier_curve<double, double, 6, true, point6_t> bezier6_t; +typedef curves::bezier_curve<double, double, true, point_t> bezier_t; +typedef curves::bezier_curve<double, double, true, waypoint_t> bezier_wp_t; +typedef curves::bezier_curve<double, double, true, point6_t> bezier6_t; typedef std::vector<std::pair<double, int> > T_time; typedef T_time::const_iterator CIT_time; diff --git a/include/hpp/bezier-com-traj/utils.hh b/include/hpp/bezier-com-traj/utils.hh index aaf39f4..9c20d04 100644 --- a/include/hpp/bezier-com-traj/utils.hh +++ b/include/hpp/bezier-com-traj/utils.hh @@ -50,7 +50,7 @@ struct waypoint_t { * @param degree required degree * @return the bernstein polynoms */ -BEZIER_COM_TRAJ_DLLAPI std::vector<spline::Bern<double> > ComputeBersteinPolynoms(const unsigned int degree); +BEZIER_COM_TRAJ_DLLAPI std::vector<curves::Bern<double> > ComputeBersteinPolynoms(const unsigned int degree); /** * @brief given the constraints of the problem, and a set of waypoints, return diff --git a/src/common_solve_methods.cpp b/src/common_solve_methods.cpp index 27e54c8..4ea7f7a 100644 --- a/src/common_solve_methods.cpp +++ b/src/common_solve_methods.cpp @@ -6,7 +6,7 @@ namespace bezier_com_traj { std::vector<waypoint6_t> ComputeDiscretizedWaypoints(const std::vector<waypoint6_t>& wps, - const std::vector<spline::Bern<double> >& berns, int numSteps) { + const std::vector<curves::Bern<double> >& berns, int numSteps) { double dt = 1. / double(numSteps); std::vector<waypoint6_t> res; for (int i = 0; i < numSteps + 1; ++i) { diff --git a/src/computeCOMTraj.cpp b/src/computeCOMTraj.cpp index 1a0da0d..da5036f 100644 --- a/src/computeCOMTraj.cpp +++ b/src/computeCOMTraj.cpp @@ -25,7 +25,7 @@ bezier_wp_t::t_point_t computeDiscretizedWwaypoints(const ProblemData& pData, do bezier_wp_t::t_point_t wps = computeWwaypoints(pData, T); bezier_wp_t::t_point_t res; const int DIM_VAR = (int)dimVar(pData); - std::vector<spline::Bern<double> > berns = ComputeBersteinPolynoms((int)wps.size() - 1); + std::vector<curves::Bern<double> > berns = ComputeBersteinPolynoms((int)wps.size() - 1); double t, b; for (CIT_time cit = timeArray.begin(); cit != timeArray.end(); ++cit) { waypoint_t w = initwp(6, DIM_VAR); @@ -277,7 +277,7 @@ ResultDataCOMTraj genTraj(ResultData resQp, const ProblemData& pData, const doub res.c_of_t_ = computeBezierCurve<bezier_t, point_t>(pData.constraints_.flag_, T, pis, res.x); computeFinalVelocity(res); computeFinalAcceleration(res); - res.dL_of_t_ = bezier_t::zero(T); + res.dL_of_t_ = bezier_t::zero(3,T); } return res; } diff --git a/src/solve_0_step.cpp b/src/solve_0_step.cpp index c4afa0f..423667e 100644 --- a/src/solve_0_step.cpp +++ b/src/solve_0_step.cpp @@ -121,7 +121,7 @@ std::vector<waypoint6_t> ComputeAllWaypoints(point_t_tC p0, point_t_tC dc0, poin wps.push_back(w3(p0, p1, g, p0X, p1X, gX, alpha)); wps.push_back(w4(p0, p1, g, p0X, p1X, gX, alpha)); if (numSteps > 0) { - std::vector<spline::Bern<double> > berns = ComputeBersteinPolynoms(4); + std::vector<curves::Bern<double> > berns = ComputeBersteinPolynoms(4); wps = ComputeDiscretizedWaypoints(wps, berns, numSteps); } return wps; @@ -137,7 +137,7 @@ std::vector<waypoint6_t> ComputeAllWaypointsAngularMomentum(point_t_tC l0, const wps.push_back(u3(l0, alpha)); wps.push_back(u4(l0, alpha)); if (numSteps > 0) { - std::vector<spline::Bern<double> > berns = ComputeBersteinPolynoms(4); + std::vector<curves::Bern<double> > berns = ComputeBersteinPolynoms(4); wps = ComputeDiscretizedWaypoints(wps, berns, numSteps); } return wps; @@ -207,7 +207,7 @@ void computedL_of_T(const ProblemData& pData, const std::vector<double>& Ts, Res wps.push_back(Vector3::Zero()); res.dL_of_t_ = bezier_t(wps.begin(), wps.end(), Ts[0], 1. / Ts[0]); } else - res.dL_of_t_ = bezier_t::zero(Ts[0]); + res.dL_of_t_ = bezier_t::zero(3,Ts[0]); } // no angular momentum for now diff --git a/src/utils.cpp b/src/utils.cpp index 75f4e66..ce7abfe 100644 --- a/src/utils.cpp +++ b/src/utils.cpp @@ -64,9 +64,9 @@ Matrix3 skew(point_t_tC x) { return res; } -std::vector<spline::Bern<double> > ComputeBersteinPolynoms(const unsigned int degree) { - std::vector<spline::Bern<double> > res; - for (unsigned int i = 0; i <= (unsigned int)degree; ++i) res.push_back(spline::Bern<double>(degree, i)); +std::vector<curves::Bern<double> > ComputeBersteinPolynoms(const unsigned int degree) { + std::vector<curves::Bern<double> > res; + for (unsigned int i = 0; i <= (unsigned int)degree; ++i) res.push_back(curves::Bern<double>(degree, i)); return res; } diff --git a/tests/test-bezier-symbolic.cpp b/tests/test-bezier-symbolic.cpp index d06373f..88beaa9 100644 --- a/tests/test-bezier-symbolic.cpp +++ b/tests/test-bezier-symbolic.cpp @@ -23,7 +23,7 @@ #include <hpp/bezier-com-traj/data.hh> #include <hpp/centroidal-dynamics/centroidal_dynamics.hh> #include "test_helper.hh" -#include <hpp/spline/bezier_curve.h> +#include <curves/bezier_curve.h> using namespace bezier_com_traj; const double T = 1.5; -- GitLab