diff --git a/CMakeLists.txt b/CMakeLists.txt index f0f94250d9bd6d2ded0cc1e9a4e2e741ed963b00..9ef850bf2bf2ef6db0caf548da87490a676cde88 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -37,7 +37,7 @@ ENDIF(BUILD_PYTHON_INTERFACE) SEARCH_FOR_BOOST() INCLUDE_DIRECTORIES(SYSTEM ${Boost_INCLUDE_DIRS}) -ADD_SUBDIRECTORY(include/curve) +ADD_SUBDIRECTORY(include/curves) ADD_SUBDIRECTORY(tests) SETUP_HPP_PROJECT_FINALIZE() diff --git a/cmake b/cmake index 61e5574a0615706aab06986f6aecf665ddc31141..cea261e3da7d383844530070356bca76d20197a8 160000 --- a/cmake +++ b/cmake @@ -1 +1 @@ -Subproject commit 61e5574a0615706aab06986f6aecf665ddc31141 +Subproject commit cea261e3da7d383844530070356bca76d20197a8 diff --git a/include/curve/CMakeLists.txt b/include/curves/CMakeLists.txt similarity index 91% rename from include/curve/CMakeLists.txt rename to include/curves/CMakeLists.txt index 1bf329e9236076a30e2fd2ea4b1dc1beee3f388b..c0f87f95b9555d1cbb879217c9f7ee0596bea727 100644 --- a/include/curve/CMakeLists.txt +++ b/include/curves/CMakeLists.txt @@ -15,7 +15,7 @@ SET(${PROJECT_NAME}_HEADERS INSTALL(FILES ${${PROJECT_NAME}_HEADERS} - DESTINATION include/curve + DESTINATION include/curves ) ADD_SUBDIRECTORY(helpers) diff --git a/include/curve/MathDefs.h b/include/curves/MathDefs.h similarity index 96% rename from include/curve/MathDefs.h rename to include/curves/MathDefs.h index c2ac664dd0dfd29e650e9b8c0449d24f5ce5472b..628898e60bf97ac176b28584fcbc8674ae8c65c8 100644 --- a/include/curve/MathDefs.h +++ b/include/curves/MathDefs.h @@ -20,7 +20,7 @@ #include <vector> #include <utility> -namespace curve{ +namespace curves{ //REF: boulic et al An inverse kinematics architecture enforcing an arbitrary number of strict priority levels template<typename _Matrix_Type_> @@ -40,5 +40,5 @@ void PseudoInverse(_Matrix_Type_& pinvmat) pinvmat = (svd.matrixV()*m_sigma_inv*svd.matrixU().transpose()); } -} // namespace curve +} // namespace curves #endif //_SPLINEMATH diff --git a/include/curve/bernstein.h b/include/curves/bernstein.h similarity index 92% rename from include/curve/bernstein.h rename to include/curves/bernstein.h index a20784359176b17c11936001e351fb252cb7a57c..800ac3447c861899370eca24181d370e7ae03482 100644 --- a/include/curve/bernstein.h +++ b/include/curves/bernstein.h @@ -18,7 +18,7 @@ #include <vector> #include <stdexcept> -namespace curve +namespace curves { /// /// \brief Computes factorial of a number. @@ -74,6 +74,6 @@ std::vector<Bern<Numeric> > makeBernstein(const unsigned int n) res.push_back(Bern<Numeric>(n, i)); return res; } -} // namespace curve +} // namespace curves #endif //_CLASS_BERNSTEIN diff --git a/include/curve/bezier_curve.h b/include/curves/bezier_curve.h similarity index 95% rename from include/curve/bezier_curve.h rename to include/curves/bezier_curve.h index 74e7767e6a02382276f9ce8f15901651e657bc26..d5d6bf124e435bf0d8d94ba10394793be2ffa11f 100644 --- a/include/curve/bezier_curve.h +++ b/include/curves/bezier_curve.h @@ -21,7 +21,7 @@ #include <iostream> -namespace curve +namespace curves { /// \class BezierCurve. /// \brief Represents a Bezier curve of arbitrary dimension and order. @@ -54,7 +54,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Dim, Safe, Point> , mult_T_(1.) , size_(std::distance(PointsBegin, PointsEnd)) , degree_(size_-1) - , bernstein_(curve::makeBernstein<num_t>((unsigned int)degree_)) + , bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_)) { assert(bernstein_.size() == size_); In it(PointsBegin); @@ -76,7 +76,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Dim, Safe, Point> , mult_T_(1.) , size_(std::distance(PointsBegin, PointsEnd)) , degree_(size_-1) - , bernstein_(curve::makeBernstein<num_t>((unsigned int)degree_)) + , bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_)) { assert(bernstein_.size() == size_); In it(PointsBegin); @@ -101,7 +101,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Dim, Safe, Point> , mult_T_(mult_T) , size_(std::distance(PointsBegin, PointsEnd)) , degree_(size_-1) - , bernstein_(curve::makeBernstein<num_t>((unsigned int)degree_)) + , bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_)) { assert(bernstein_.size() == size_); In it(PointsBegin); @@ -124,7 +124,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Dim, Safe, Point> , mult_T_(1.) , size_(std::distance(PointsBegin, PointsEnd)+4) , degree_(size_-1) - , bernstein_(curve::makeBernstein<num_t>((unsigned int)degree_)) + , bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_)) { if(Safe && (size_<1 || T_ <= 0.)) throw std::out_of_range("can't create bezier min bound is higher than max bound"); diff --git a/include/curve/bezier_polynom_conversion.h b/include/curves/bezier_polynom_conversion.h similarity index 94% rename from include/curve/bezier_polynom_conversion.h rename to include/curves/bezier_polynom_conversion.h index a2700b163717ced8b9d915685fc263cae4443069..6829f98d0846be4359807dd6562b25f1b79bddf4 100644 --- a/include/curve/bezier_polynom_conversion.h +++ b/include/curves/bezier_polynom_conversion.h @@ -21,7 +21,7 @@ #include <iostream> -namespace curve +namespace curves { /// \brief Provides methods for converting a curve from a bernstein representation /// to a polynom representation. @@ -64,6 +64,6 @@ Bezier from_polynom(const Polynom& polynom) typedef Bezier::cit_point_t cit_point_t; typedef Bezier::bezier_curve_t bezier_curve_t; }*/ -} // namespace curve +} // namespace curves #endif //_BEZIER_POLY_CONVERSION diff --git a/include/curve/cubic_spline.h b/include/curves/cubic_spline.h similarity index 94% rename from include/curve/cubic_spline.h rename to include/curves/cubic_spline.h index a852d8e72d3a8a828347fb114f447729d10a0ea4..4e2efed0e94f9240d8d5e86ef86be7d3957c074a 100644 --- a/include/curve/cubic_spline.h +++ b/include/curves/cubic_spline.h @@ -20,7 +20,7 @@ #include <stdexcept> -namespace curve +namespace curves { /// \brief Creates coefficient vector of a cubic spline defined on the interval /// \f$[t_{min}, t_{max}]\f$. It follows the equation : @@ -41,6 +41,6 @@ polynom<Time,Numeric,Dim,Safe,Point,T_Point> create_cubic(Point const& a, Point T_Point coeffs = make_cubic_vector<Point, T_Point>(a,b,c,d); return polynom<Time,Numeric,Dim,Safe,Point,T_Point>(coeffs.begin(),coeffs.end(), t_min, t_max); } -} // namespace curve +} // namespace curves #endif //_STRUCT_CUBICSPLINE diff --git a/include/curve/curve_abc.h b/include/curves/curve_abc.h similarity index 94% rename from include/curve/curve_abc.h rename to include/curves/curve_abc.h index 72aac2d98a917bad536c2eb129c853f32b5b61b4..a943eb8911214e942ecebaef070dabb54d653932 100644 --- a/include/curve/curve_abc.h +++ b/include/curves/curve_abc.h @@ -16,7 +16,7 @@ #include <functional> -namespace curve +namespace curves { /// \struct curve_abc /// \brief Represents a curve of dimension Dim @@ -63,6 +63,6 @@ struct curve_abc : std::unary_function<Time, Point> /*Helpers*/ }; -} // namespace curve +} // namespace curves #endif //_STRUCT_CURVE_ABC diff --git a/include/curve/curve_constraint.h b/include/curves/curve_constraint.h similarity index 94% rename from include/curve/curve_constraint.h rename to include/curves/curve_constraint.h index 5b4e8efc9b82d2c3e097dd3675aa41bef8f286e8..d3710c9fb40e396bce15fcc55989d7f2bb074623 100644 --- a/include/curve/curve_constraint.h +++ b/include/curves/curve_constraint.h @@ -17,7 +17,7 @@ #include <functional> #include <vector> -namespace curve +namespace curves { template <typename Point> struct curve_constraints @@ -32,5 +32,5 @@ struct curve_constraints point_t end_vel; point_t end_acc; }; -} // namespace curve +} // namespace curves #endif //_CLASS_CUBICZEROVELACC diff --git a/include/curve/exact_cubic.h b/include/curves/exact_cubic.h similarity index 96% rename from include/curve/exact_cubic.h rename to include/curves/exact_cubic.h index e33f934b8feaa2354d7387f61a54d65232a19072..693109c02c72b580fb0fdbcf7dc3f47e9620632b 100644 --- a/include/curve/exact_cubic.h +++ b/include/curves/exact_cubic.h @@ -29,7 +29,7 @@ #include <functional> #include <vector> -namespace curve +namespace curves { /// \class ExactCubic. /// \brief Represents a set of cubic splines defining a continuous function @@ -201,6 +201,6 @@ struct exact_cubic : public curve_abc<Time, Numeric, Dim, Safe, Point> t_spline_t subSplines_; // const /*Attributes*/ }; -} // namespace curve +} // namespace curves #endif //_CLASS_EXACTCUBIC diff --git a/include/curve/helpers/CMakeLists.txt b/include/curves/helpers/CMakeLists.txt similarity index 79% rename from include/curve/helpers/CMakeLists.txt rename to include/curves/helpers/CMakeLists.txt index 7a849f3810093da39a1fb5d2bf1a2ac92500aa1f..680a55b60ff892c63c9e926162bed4b049cd5de2 100644 --- a/include/curve/helpers/CMakeLists.txt +++ b/include/curves/helpers/CMakeLists.txt @@ -5,5 +5,5 @@ SET(${PROJECT_NAME}_HELPERS_HEADERS INSTALL(FILES ${${PROJECT_NAME}_HELPERS_HEADERS} - DESTINATION include/curve/helpers + DESTINATION include/curves/helpers ) diff --git a/include/curve/helpers/effector_spline.h b/include/curves/helpers/effector_spline.h similarity index 98% rename from include/curve/helpers/effector_spline.h rename to include/curves/helpers/effector_spline.h index b4cfa07e3af38101e772dedb352863edc7917194..9d9cd4216a63b14c83515aa334203cabbbcb68de 100644 --- a/include/curve/helpers/effector_spline.h +++ b/include/curves/helpers/effector_spline.h @@ -20,9 +20,9 @@ #ifndef _CLASS_EFFECTORSPLINE #define _CLASS_EFFECTORSPLINE -#include "curve/spline_deriv_constraint.h" +#include "curves/spline_deriv_constraint.h" -namespace curve +namespace curves { namespace helpers { @@ -118,5 +118,5 @@ exact_cubic_t* effector_spline( return new exact_cubic_t(splines); } } // namespace helpers -} // namespace curve +} // namespace curves #endif //_CLASS_EFFECTORSPLINE diff --git a/include/curve/helpers/effector_spline_rotation.h b/include/curves/helpers/effector_spline_rotation.h similarity index 98% rename from include/curve/helpers/effector_spline_rotation.h rename to include/curves/helpers/effector_spline_rotation.h index 391a6c46f090602214042e1000510608984ab65f..9d7ff42239394273ba0bd11ffa70678f79db0c10 100644 --- a/include/curve/helpers/effector_spline_rotation.h +++ b/include/curves/helpers/effector_spline_rotation.h @@ -20,11 +20,11 @@ #ifndef _CLASS_EFFECTOR_SPLINE_ROTATION #define _CLASS_EFFECTOR_SPLINE_ROTATION -#include "curve/helpers/effector_spline.h" -#include "curve/curve_abc.h" +#include "curves/helpers/effector_spline.h" +#include "curves/curve_abc.h" #include <Eigen/Geometry> -namespace curve +namespace curves { namespace helpers { @@ -252,5 +252,5 @@ class effector_spline_rotation }; } // namespace helpers -} // namespace curve +} // namespace curves #endif //_CLASS_EFFECTOR_SPLINE_ROTATION diff --git a/include/curve/linear_variable.h b/include/curves/linear_variable.h similarity index 95% rename from include/curve/linear_variable.h rename to include/curves/linear_variable.h index 5d91fe19ec2bf461b9721d3a868ff9ff19701542..5a1dc4961e2fa0f14060d95f9dc4bafc253e31bc 100644 --- a/include/curve/linear_variable.h +++ b/include/curves/linear_variable.h @@ -19,7 +19,7 @@ #include <Eigen/Core> #include <stdexcept> -namespace curve +namespace curves { template <int Dim, typename Numeric=double> struct linear_variable{ @@ -196,6 +196,6 @@ variables<V> operator/(const variables<V>& w,const double k) return res; } -} // namespace curve +} // namespace curves #endif //_CLASS_LINEAR_VARIABLE diff --git a/include/curve/optimization/OptimizeSpline.h b/include/curves/optimization/OptimizeSpline.h similarity index 99% rename from include/curve/optimization/OptimizeSpline.h rename to include/curves/optimization/OptimizeSpline.h index 8a779a7bb3299b25cbbe90f291f1bfdcb76ac2e8..1107a582fceaec594cab7aec490d2f76201425cd 100644 --- a/include/curve/optimization/OptimizeSpline.h +++ b/include/curves/optimization/OptimizeSpline.h @@ -12,15 +12,15 @@ #ifndef _CLASS_SPLINEOPTIMIZER #define _CLASS_SPLINEOPTIMIZER -#include "curve/MathDefs.h" -#include "curve/exact_cubic.h" +#include "curves/MathDefs.h" +#include "curves/exact_cubic.h" #include "mosek/mosek.h" #include <Eigen/SparseCore> #include <utility> -namespace curve +namespace curves { /// \class SplineOptimizer /// \brief Mosek connection to produce optimized splines @@ -516,5 +516,5 @@ inline exact_cubic<Time, Numeric, Dim, Safe, Point>* return res; } -} // namespace curve +} // namespace curves #endif //_CLASS_SPLINEOPTIMIZER diff --git a/include/curve/polynom.h b/include/curves/polynom.h similarity index 96% rename from include/curve/polynom.h rename to include/curves/polynom.h index 2aca2fed9d47429c5e3c221343985bbdd283dc67..2fd55ae14a0a1194b1d6b3a39be8460cd0e1503c 100644 --- a/include/curve/polynom.h +++ b/include/curves/polynom.h @@ -23,7 +23,7 @@ #include <functional> #include <stdexcept> -namespace curve +namespace curves { /// \class polynom /// \brief Represents a polynomf arbitrary order defined on the interval @@ -199,6 +199,6 @@ struct polynom : public curve_abc<Time, Numeric, Dim, Safe, Point> return res; } }; //class polynom -} // namespace curve +} // namespace curves #endif //_STRUCT_POLYNOM diff --git a/include/curve/quintic_spline.h b/include/curves/quintic_spline.h similarity index 94% rename from include/curve/quintic_spline.h rename to include/curves/quintic_spline.h index 8a4553bdb787c821787a7109d6185d6941e62539..3ff0cf585a4f70976ccb35ea2cac46625ca84a3b 100644 --- a/include/curve/quintic_spline.h +++ b/include/curves/quintic_spline.h @@ -20,7 +20,7 @@ #include <stdexcept> -namespace curve +namespace curves { /// \brief Creates coefficient vector of a quintic spline defined on the interval /// \f$[t_{min}, t_{max}]\f$. It follows the equation : @@ -44,6 +44,6 @@ polynom<Time,Numeric,Dim,Safe,Point,T_Point> create_quintic(Point const& a, Poin T_Point coeffs = make_quintic_vector<Point, T_Point>(a,b,c,d,e,f); return polynom<Time,Numeric,Dim,Safe,Point,T_Point>(coeffs.begin(),coeffs.end(), t_min, t_max); } -} // namespace curve +} // namespace curves #endif //_STRUCT_QUINTIC_SPLINE diff --git a/include/curve/spline_deriv_constraint.h b/include/curves/spline_deriv_constraint.h similarity index 97% rename from include/curve/spline_deriv_constraint.h rename to include/curves/spline_deriv_constraint.h index 16ececf72e4a23984b635e02a0ffd40ce274ecbc..9f5c332371a37d89713e7d187cdbe6e3e587c87c 100644 --- a/include/curve/spline_deriv_constraint.h +++ b/include/curves/spline_deriv_constraint.h @@ -28,7 +28,7 @@ #include <functional> #include <vector> -namespace curve +namespace curves { /// \class spline_deriv_constraint. /// \brief Represents a set of cubic splines defining a continuous function @@ -137,6 +137,6 @@ struct spline_deriv_constraint : public exact_cubic<Time, Numeric, Dim, Safe, Po private: /* Constructors - destructors */ }; -} // namespace curve +} // namespace curves #endif //_CLASS_CUBICZEROVELACC diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index a820c7cf843715a523c9dfde967a9642a411a765..a356071ca94360cc9cfd53a45a2d975d6dbaea46 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,5 +1,5 @@ SET(${PY_NAME}_BINDINGS_SOURCES - curve_python.cpp + curves_python.cpp python_variables.cpp python_variables.h ) @@ -15,4 +15,4 @@ ENDIF(APPLE) INSTALL(TARGETS ${PY_NAME} DESTINATION ${PYTHON_SITELIB}) -ADD_PYTHON_UNIT_TEST("python-curve" "python/test/test.py" "python") +ADD_PYTHON_UNIT_TEST("python-curves" "python/test/test.py" "python") diff --git a/python/curve_python.cpp b/python/curves_python.cpp similarity index 93% rename from python/curve_python.cpp rename to python/curves_python.cpp index ee96e7f13055bd13e76c4e855c3b3e0ec6b6b423..6c843d025a6396377ac5d5220c9409cd2681877a 100644 --- a/python/curve_python.cpp +++ b/python/curves_python.cpp @@ -1,10 +1,10 @@ -#include "curve/bezier_curve.h" -#include "curve/polynom.h" -#include "curve/exact_cubic.h" -#include "curve/spline_deriv_constraint.h" -#include "curve/curve_constraint.h" -#include "curve/bezier_polynom_conversion.h" -#include "curve/bernstein.h" +#include "curves/bezier_curve.h" +#include "curves/polynom.h" +#include "curves/exact_cubic.h" +#include "curves/spline_deriv_constraint.h" +#include "curves/curve_constraint.h" +#include "curves/bezier_polynom_conversion.h" +#include "curves/bernstein.h" #include "python_definitions.h" #include "python_variables.h" @@ -17,7 +17,7 @@ #include <boost/python.hpp> /*** TEMPLATE SPECIALIZATION FOR PYTHON ****/ -using namespace curve; +using namespace curves; typedef double real; typedef Eigen::Vector3d point_t; typedef Eigen::Matrix<double, 6, 1, 0, 6, 1> point6_t; @@ -33,20 +33,20 @@ typedef std::vector<Waypoint> T_Waypoint; typedef std::pair<real, point6_t> Waypoint6; typedef std::vector<Waypoint6> T_Waypoint6; -typedef curve::bezier_curve <real, real, 3, true, point_t> bezier3_t; -typedef curve::bezier_curve <real, real, 6, true, point6_t> bezier6_t; -typedef curve::polynom <real, real, 3, true, point_t, t_point_t> polynom_t; -typedef curve::exact_cubic <real, real, 3, true, point_t, t_point_t> exact_cubic_t; +typedef curves::bezier_curve <real, real, 3, true, point_t> bezier3_t; +typedef curves::bezier_curve <real, real, 6, true, point6_t> bezier6_t; +typedef curves::polynom <real, real, 3, true, point_t, t_point_t> polynom_t; +typedef curves::exact_cubic <real, real, 3, true, point_t, t_point_t> exact_cubic_t; typedef polynom_t::coeff_t coeff_t; typedef std::pair<real, point_t> waypoint_t; typedef std::vector<waypoint_t, Eigen::aligned_allocator<point_t> > t_waypoint_t; -typedef curve::Bern<double> bernstein_t; +typedef curves::Bern<double> bernstein_t; -typedef curve::spline_deriv_constraint <real, real, 3, true, point_t, t_point_t> spline_deriv_constraint_t; -typedef curve::curve_constraints<point_t> curve_constraints_t; -typedef curve::curve_constraints<point6_t> curve_constraints6_t; +typedef curves::spline_deriv_constraint <real, real, 3, true, point_t, t_point_t> spline_deriv_constraint_t; +typedef curves::curve_constraints<point_t> curve_constraints_t; +typedef curves::curve_constraints<point6_t> curve_constraints6_t; /*** TEMPLATE SPECIALIZATION FOR PYTHON ****/ EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(bernstein_t) @@ -57,7 +57,7 @@ EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(exact_cubic_t) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curve_constraints_t) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(spline_deriv_constraint_t) -namespace curve +namespace curves { using namespace boost::python; @@ -346,4 +346,4 @@ BOOST_PYTHON_MODULE(curves) } -} // namespace curve +} // namespace curves diff --git a/python/python_definitions.h b/python/python_definitions.h index f5ddc62282cca423301a132ee53466ff553f3e78..d1b13a0d007dbf6335a2ca0baf62070fc90567a2 100644 --- a/python/python_definitions.h +++ b/python/python_definitions.h @@ -1,5 +1,5 @@ -#include "curve/bezier_curve.h" -#include "curve/linear_variable.h" +#include "curves/bezier_curve.h" +#include "curves/linear_variable.h" #include <vector> @@ -7,7 +7,7 @@ #define _DEFINITION_PYTHON_BINDINGS -namespace curve +namespace curves { typedef double real; @@ -37,7 +37,7 @@ T_Point vectorFromEigenArray(const PointList& array) return res; } -} //namespace curve. +} //namespace curves #endif //_DEFINITION_PYTHON_BINDINGS diff --git a/python/python_variables.cpp b/python/python_variables.cpp index cb1808dc07015fa807fd84d752d9ab9cef93c68c..715c0d9550847c4645aacf863eb1a598e8ce0f2e 100644 --- a/python/python_variables.cpp +++ b/python/python_variables.cpp @@ -4,7 +4,7 @@ #include <Eigen/Core> -namespace curve +namespace curves { std::vector<linear_variable_3_t> matrix3DFromEigenArray(const point_list_t& matrices, const point_list_t& vectors) @@ -101,4 +101,4 @@ LinearBezierVector* split(const bezier_linear_variable_t& self, const vectorX_t } } - // namespace curve + // namespace curves diff --git a/python/python_variables.h b/python/python_variables.h index 1c11850e135324715f739aeade94f6f7583590fc..393284204cb61610870e2a041f69445cec7a54e4 100644 --- a/python/python_variables.h +++ b/python/python_variables.h @@ -1,5 +1,5 @@ -#include "curve/bezier_curve.h" -#include "curve/linear_variable.h" +#include "curves/bezier_curve.h" +#include "curves/linear_variable.h" #include "python_definitions.h" @@ -9,12 +9,12 @@ #define _VARIABLES_PYTHON_BINDINGS -namespace curve +namespace curves { static const int dim = 3; -typedef curve::linear_variable<dim, real> linear_variable_3_t; -typedef curve::variables<linear_variable_3_t> variables_3_t; -typedef curve::bezier_curve <real, real, dim, true, variables_3_t> bezier_linear_variable_t; +typedef curves::linear_variable<dim, real> linear_variable_3_t; +typedef curves::variables<linear_variable_3_t> variables_3_t; +typedef curves::bezier_curve <real, real, dim, true, variables_3_t> bezier_linear_variable_t; /*linear variable control points*/ diff --git a/python/test/test.py b/python/test/test.py index d42bb3ce120cd97c4807f4c8c3b41c8ef60e8843..4c93b48b0aaea71e1ffa3b640dcc58e30e822f01 100644 --- a/python/test/test.py +++ b/python/test/test.py @@ -12,7 +12,7 @@ import unittest from curves import bezier3, bezier6, curve_constraints, exact_cubic, from_bezier, polynom, spline_deriv_constraint -class TestCurve(unittest.TestCase): +class TestCurves(unittest.TestCase): #def print_str(self, inStr): # print inStr # return diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 2365cf2b0c7b67419fe488b04c8401cc171ace87..cf060241f6818fefb1b8ea5eef8b419fabe76ab1 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -1,4 +1,4 @@ ADD_UNIT_TEST( - curve_tests Main.cpp + curves_tests Main.cpp ) -PKG_CONFIG_USE_DEPENDENCY(curve_tests eigen3) +PKG_CONFIG_USE_DEPENDENCY(curves_tests eigen3) diff --git a/tests/Main.cpp b/tests/Main.cpp index 7c0e004b43423c74bee40b112f960199048ce9e9..162e20261e32065dc6b6ba9fa68835bd4e1767ed 100644 --- a/tests/Main.cpp +++ b/tests/Main.cpp @@ -1,11 +1,11 @@ -#include "curve/exact_cubic.h" -#include "curve/bezier_curve.h" -#include "curve/polynom.h" -#include "curve/spline_deriv_constraint.h" -#include "curve/helpers/effector_spline.h" -#include "curve/helpers/effector_spline_rotation.h" -#include "curve/bezier_polynom_conversion.h" +#include "curves/exact_cubic.h" +#include "curves/bezier_curve.h" +#include "curves/polynom.h" +#include "curves/spline_deriv_constraint.h" +#include "curves/helpers/effector_spline.h" +#include "curves/helpers/effector_spline_rotation.h" +#include "curves/bezier_polynom_conversion.h" #include <string> #include <iostream> @@ -13,7 +13,7 @@ using namespace std; -namespace curve +namespace curves { typedef Eigen::Vector3d point_t; typedef std::vector<point_t,Eigen::aligned_allocator<point_t> > t_point_t; @@ -46,9 +46,9 @@ bool QuasiEqual(const double a, const double b, const float margin) const double margin = 0.001; -} // namespace curve +} // namespace curves -using namespace curve; +using namespace curves; ostream& operator<<(ostream& os, const point_t& pt) { @@ -464,7 +464,7 @@ void BezierToPolynomConversionTest(bool& error) /*Exact Cubic Function tests*/ void ExactCubicNoErrorTest(bool& error) { - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i <= 1; i = i + 0.2) { waypoints.push_back(std::make_pair(i,point_t(i,i,i))); @@ -510,7 +510,7 @@ void ExactCubicNoErrorTest(bool& error) /*Exact Cubic Function tests*/ void ExactCubicTwoPointsTest(bool& error) { - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i < 2; ++i) { waypoints.push_back(std::make_pair(i,point_t(i,i,i))); @@ -527,7 +527,7 @@ void ExactCubicTwoPointsTest(bool& error) void ExactCubicOneDimTest(bool& error) { - curve::T_WaypointOne waypoints; + curves::T_WaypointOne waypoints; point_one zero; zero(0,0) = 9; point_one one; one(0,0) = 14; point_one two; two(0,0) = 25; @@ -544,7 +544,7 @@ void ExactCubicOneDimTest(bool& error) ComparePoints(one, res1, errmsg, error); } -void CheckWayPointConstraint(const std::string& errmsg, const double step, const curve::T_Waypoint& /*wayPoints*/, const exact_cubic_t* curve, bool& error ) +void CheckWayPointConstraint(const std::string& errmsg, const double step, const curves::T_Waypoint& /*wayPoints*/, const exact_cubic_t* curve, bool& error ) { point_t res1; for(double i = 0; i <= 1; i = i + step) @@ -563,7 +563,7 @@ void CheckDerivative(const std::string& errmsg, const double eval_point, const s void ExactCubicPointsCrossedTest(bool& error) { - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i <= 1; i = i + 0.2) { waypoints.push_back(std::make_pair(i,point_t(i,i,i))); @@ -576,7 +576,7 @@ void ExactCubicPointsCrossedTest(bool& error) void ExactCubicVelocityConstraintsTest(bool& error) { - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i <= 1; i = i + 0.2) { waypoints.push_back(std::make_pair(i,point_t(i,i,i))); @@ -625,7 +625,7 @@ void CheckPointOnline(const std::string& errmsg, const point_t& A, const point_t void EffectorTrajectoryTest(bool& error) { // create arbitrary trajectory - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i <= 10; i = i + 2) { waypoints.push_back(std::make_pair(i,point_t(i,i,i))); @@ -682,7 +682,7 @@ double GetXRotFromQuat(helpers::quat_ref_const_t q) void EffectorSplineRotationNoRotationTest(bool& error) { // create arbitrary trajectory - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i <= 10; i = i + 2) { waypoints.push_back(std::make_pair(i,point_t(i,i,i))); @@ -704,7 +704,7 @@ void EffectorSplineRotationNoRotationTest(bool& error) void EffectorSplineRotationRotationTest(bool& error) { // create arbitrary trajectory - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i <= 10; i = i + 2) { waypoints.push_back(std::make_pair(i,point_t(i,i,i))); @@ -727,7 +727,7 @@ void EffectorSplineRotationRotationTest(bool& error) void EffectorSplineRotationWayPointRotationTest(bool& error) { // create arbitrary trajectory - curve::T_Waypoint waypoints; + curves::T_Waypoint waypoints; for(double i = 0; i <= 10; i = i + 2) { waypoints.push_back(std::make_pair(i,point_t(i,i,i)));