Commit fe6e7280 authored by JasonChmn's avatar JasonChmn
Browse files

Change namespace and edit names in spline to curve for more generalization

parent 88ba5811
......@@ -5,7 +5,7 @@ INCLUDE(cmake/test.cmake)
INCLUDE(cmake/python.cmake)
SET(PROJECT_ORG humanoid-path-planner)
SET(PROJECT_NAME hpp-spline)
SET(PROJECT_NAME curves)
SET(PROJECT_DESCRIPTION
"template based classes for creating and manipulating spline and bezier curves. Comes with extra options specific to end-effector trajectories in robotics."
)
......@@ -35,7 +35,7 @@ IF(BUILD_PYTHON_INTERFACE)
ENDIF(BUILD_PYTHON_INTERFACE)
ADD_SUBDIRECTORY(include/hpp/spline)
ADD_SUBDIRECTORY(include/curve)
ADD_SUBDIRECTORY(tests)
SETUP_PROJECT_FINALIZE()
Subproject commit 320c636960b03b3bad7c7a08bd2e104951f42bc3
Subproject commit cea261e3da7d383844530070356bca76d20197a8
......@@ -15,7 +15,7 @@ SET(${PROJECT_NAME}_HEADERS
INSTALL(FILES
${${PROJECT_NAME}_HEADERS}
DESTINATION include/hpp/spline
DESTINATION include/curve
)
ADD_SUBDIRECTORY(helpers)
......@@ -21,7 +21,7 @@
#include <vector>
#include <utility>
namespace spline{
namespace curve{
//REF: boulic et al An inverse kinematics architecture enforcing an arbitrary number of strict priority levels
template<typename _Matrix_Type_>
......@@ -41,6 +41,6 @@ void PseudoInverse(_Matrix_Type_& pinvmat)
pinvmat = (svd.matrixV()*m_sigma_inv*svd.matrixU().transpose());
}
} // namespace spline
} // namespace curve
#endif //_SPLINEMATH
......@@ -18,7 +18,7 @@
#include <vector>
#include <stdexcept>
namespace spline
namespace curve
{
///
/// \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 spline
} // namespace curve
#endif //_CLASS_BERNSTEIN
......@@ -21,7 +21,7 @@
#include <iostream>
namespace spline
namespace curve
{
/// \class BezierCurve
/// \brief Represents a Bezier curve of arbitrary dimension and order.
......@@ -51,7 +51,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Dim, Safe, Point>
, mult_T_(1.)
, size_(std::distance(PointsBegin, PointsEnd))
, degree_(size_-1)
, bernstein_(spline::makeBernstein<num_t>((unsigned int)degree_))
, bernstein_(curve::makeBernstein<num_t>((unsigned int)degree_))
{
assert(bernstein_.size() == size_);
In it(PointsBegin);
......@@ -70,7 +70,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Dim, Safe, Point>
, mult_T_(1.)
, size_(std::distance(PointsBegin, PointsEnd))
, degree_(size_-1)
, bernstein_(spline::makeBernstein<num_t>((unsigned int)degree_))
, bernstein_(curve::makeBernstein<num_t>((unsigned int)degree_))
{
assert(bernstein_.size() == size_);
In it(PointsBegin);
......@@ -91,7 +91,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_(spline::makeBernstein<num_t>((unsigned int)degree_))
, bernstein_(curve::makeBernstein<num_t>((unsigned int)degree_))
{
assert(bernstein_.size() == size_);
In it(PointsBegin);
......@@ -113,7 +113,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_(spline::makeBernstein<num_t>((unsigned int)degree_))
, bernstein_(curve::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");
......@@ -364,6 +364,6 @@ struct bezier_curve : public curve_abc<Time, Numeric, Dim, Safe, Point>
return bezier_curve_t(ts.begin(), ts.end(),T);
}
};
}
} // namespace curve
#endif //_CLASS_BEZIERCURVE
......@@ -21,7 +21,7 @@
#include <iostream>
namespace spline
namespace curve
{
/// \brief Provides methods for converting a curve from a bernstein representation
/// to a polynom representation
......@@ -67,6 +67,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
#endif //_BEZIER_POLY_CONVERSION
......@@ -20,7 +20,7 @@
#include <stdexcept>
namespace spline
namespace curve
{
/// \brief Creates coefficient vector of a cubic spline defined on the interval
/// [tBegin, tEnd]. 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(), min, max);
}
}
} // namespace curve
#endif //_STRUCT_CUBICSPLINE
......@@ -16,7 +16,7 @@
#include <functional>
namespace spline
namespace curve
{
/// \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
#endif //_STRUCT_CURVE_ABC
......@@ -17,7 +17,7 @@
#include <functional>
#include <vector>
namespace spline
namespace curve
{
template <typename Point>
struct curve_constraints
......@@ -32,5 +32,5 @@ struct curve_constraints
point_t end_vel;
point_t end_acc;
};
}
} // namespace curve
#endif //_CLASS_CUBICZEROVELACC
......@@ -29,7 +29,7 @@
#include <functional>
#include <vector>
namespace spline
namespace curve
{
/// \class ExactCubic
/// \brief Represents a set of cubic splines defining a continuous function
......@@ -198,6 +198,6 @@ struct exact_cubic : public curve_abc<Time, Numeric, Dim, Safe, Point>
t_spline_t subSplines_; // const
/*Attributes*/
};
}
} // namespace curve
#endif //_CLASS_EXACTCUBIC
......@@ -5,5 +5,5 @@ SET(${PROJECT_NAME}_HELPERS_HEADERS
INSTALL(FILES
${${PROJECT_NAME}_HELPERS_HEADERS}
DESTINATION include/hpp/spline/helpers
DESTINATION include/curve/helpers
)
......@@ -20,9 +20,9 @@
#ifndef _CLASS_EFFECTORSPLINE
#define _CLASS_EFFECTORSPLINE
#include "hpp/spline/spline_deriv_constraint.h"
#include "curve/spline_deriv_constraint.h"
namespace spline
namespace curve
{
namespace helpers
{
......@@ -117,6 +117,6 @@ exact_cubic_t* effector_spline(
splines.push_back(end_spline);
return new exact_cubic_t(splines);
}
}
}
} // namespace helpers
} // namespace curve
#endif //_CLASS_EFFECTORSPLINE
......@@ -20,11 +20,11 @@
#ifndef _CLASS_EFFECTOR_SPLINE_ROTATION
#define _CLASS_EFFECTOR_SPLINE_ROTATION
#include "hpp/spline/helpers/effector_spline.h"
#include "hpp/spline/curve_abc.h"
#include "curve/helpers/effector_spline.h"
#include "curve/curve_abc.h"
#include <Eigen/Geometry>
namespace spline
namespace curve
{
namespace helpers
{
......@@ -252,5 +252,5 @@ class effector_spline_rotation
};
} // namespace helpers
} // namespace spline
} // namespace curve
#endif //_CLASS_EFFECTOR_SPLINE_ROTATION
......@@ -19,7 +19,7 @@
#include <Eigen/Core>
#include <stdexcept>
namespace spline
namespace curve
{
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 spline
} // namespace curve
#endif //_CLASS_LINEAR_VARIABLE
......@@ -23,7 +23,7 @@
#include <functional>
#include <stdexcept>
namespace spline
namespace curve
{
/// \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
#endif //_STRUCT_POLYNOM
......@@ -20,7 +20,7 @@
#include <stdexcept>
namespace spline
namespace curve
{
/// \brief Creates coefficient vector of a quintic spline defined on the interval
/// [tBegin, tEnd]. It follows the equation
......@@ -43,6 +43,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(), min, max);
}
}
} // namespace curve
#endif //_STRUCT_QUINTIC_SPLINE
......@@ -28,7 +28,7 @@
#include <functional>
#include <vector>
namespace spline
namespace curve
{
/// \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
#endif //_CLASS_CUBICZEROVELACC
......@@ -3,7 +3,7 @@ STRING(REGEX REPLACE "-" "_" PY_NAME ${PROJECT_NAME})
ADD_REQUIRED_DEPENDENCY("eigenpy")
# Define the wrapper library that wraps our library
add_library( ${PY_NAME} SHARED spline_python.cpp python_variables.cpp python_variables.h )
add_library( ${PY_NAME} SHARED curve_python.cpp python_variables.cpp python_variables.h )
#~ target_link_libraries( centroidal_dynamics ${Boost_LIBRARIES} ${PROJECT_NAME} )
# don't prepend wrapper library name with lib
set_target_properties( ${PY_NAME} PROPERTIES PREFIX "" )
......@@ -18,4 +18,4 @@ INSTALL(
TARGETS ${PY_NAME} DESTINATION ${PYTHON_SITELIB}
)
ADD_PYTHON_UNIT_TEST("python-spline" "python/test/test.py" "python")
ADD_PYTHON_UNIT_TEST("python-curve" "python/test/test.py" "python")
#include "hpp/spline/bezier_curve.h"
#include "hpp/spline/polynom.h"
#include "hpp/spline/exact_cubic.h"
#include "hpp/spline/spline_deriv_constraint.h"
#include "hpp/spline/curve_constraint.h"
#include "hpp/spline/bezier_polynom_conversion.h"
#include "hpp/spline/bernstein.h"
#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 "python_definitions.h"
#include "python_variables.h"
......@@ -17,22 +17,22 @@
#include <boost/python.hpp>
/*** TEMPLATE SPECIALIZATION FOR PYTHON ****/
using namespace spline;
using namespace curve;
typedef spline::bezier_curve <real, real, 3, true, point_t> bezier_t;
typedef spline::bezier_curve <real, real, 6, true, point6_t> bezier6_t;
typedef spline::polynom <real, real, 3, true, point_t, t_point_t> polynom_t;
typedef spline::exact_cubic <real, real, 3, true, point_t, t_point_t> exact_cubic_t;
typedef curve::bezier_curve <real, real, 3, true, point_t> bezier_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 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 spline::Bern<double> bernstein_t;
typedef curve::Bern<double> bernstein_t;
typedef spline::spline_deriv_constraint <real, real, 3, true, point_t, t_point_t> spline_deriv_constraint_t;
typedef spline::curve_constraints<point_t> curve_constraints_t;
typedef spline::curve_constraints<point6_t> curve_constraints6_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;
/*** TEMPLATE SPECIALIZATION FOR PYTHON ****/
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(bernstein_t)
......@@ -43,7 +43,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 spline
namespace curve
{
using namespace boost::python;
......@@ -186,7 +186,7 @@ void set_end_acc(curve_constraints_t& c, const point_t& val)
BOOST_PYTHON_MODULE(hpp_spline)
BOOST_PYTHON_MODULE(curves)
{
/** BEGIN eigenpy init**/
eigenpy::enableEigenPy();
......@@ -332,4 +332,4 @@ BOOST_PYTHON_MODULE(hpp_spline)
}
} // namespace spline
} // namespace curve
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment