...
 
Commits (50)
......@@ -58,16 +58,16 @@ SET(${PROJECT_NAME}_HEADERS
include/${PROJECT_NAME}/MathDefs.h
include/${PROJECT_NAME}/polynomial.h
include/${PROJECT_NAME}/bezier_curve.h
include/${PROJECT_NAME}/cubic_spline.h
include/${PROJECT_NAME}/curve_constraint.h
include/${PROJECT_NAME}/quintic_spline.h
include/${PROJECT_NAME}/linear_variable.h
include/${PROJECT_NAME}/quadratic_variable.h
include/${PROJECT_NAME}/cubic_hermite_spline.h
include/${PROJECT_NAME}/piecewise_curve.h
include/${PROJECT_NAME}/so3_linear.h
include/${PROJECT_NAME}/se3_curve.h
include/${PROJECT_NAME}/sinusoidal.h
include/${PROJECT_NAME}/fwd.h
include/${PROJECT_NAME}/constant_curve.h
include/${PROJECT_NAME}/helpers/effector_spline.h
include/${PROJECT_NAME}/helpers/effector_spline_rotation.h
include/${PROJECT_NAME}/optimization/definitions.h
......
Subproject commit ea65d78d2ab708da3ab736122cd19859bf4e46f8
Subproject commit fb4c22c319ec5320f9a85527eb1a4130954846f5
......@@ -21,7 +21,7 @@
#include <vector>
#include <utility>
namespace curves {
// REF: boulic et al An inverse kinematics architecture enforcing an arbitrary number of strict priority levels
/// \brief An inverse kinematics architecture enforcing an arbitrary number of strict priority levels (Reference : Boulic et Al. 2003)
template <typename _Matrix_Type_>
void PseudoInverse(_Matrix_Type_& pinvmat) {
Eigen::JacobiSVD<_Matrix_Type_> svd(pinvmat, Eigen::ComputeFullU | Eigen::ComputeFullV);
......
......@@ -31,7 +31,7 @@ inline unsigned int bin(const unsigned int n, const unsigned int k) {
}
/// \class Bernstein.
/// \brief Computes a Bernstein polynome.
/// \brief Computes a Bernstein polynomial.
///
template <typename Numeric = double>
struct Bern {
......@@ -40,6 +40,9 @@ struct Bern {
~Bern() {}
/// \brief Evaluation of Bernstein polynomial at value u.
/// \param u : value between 0 and 1.
/// \return Evaluation corresponding at value u.
Numeric operator()(const Numeric u) const {
if (!(u >= 0. && u <= 1.)) {
throw std::invalid_argument("u needs to be betwen 0 and 1.");
......@@ -47,11 +50,17 @@ struct Bern {
return bin_m_i_ * (pow(u, i_)) * pow((1 - u), m_minus_i);
}
/// \brief Check if actual Bernstein polynomial and other are approximately equal.
/// \param other : the other Bernstein polynomial to check.
/// \return true if the two Bernstein polynomials are approximately equals.
virtual bool operator==(const Bern& other) const {
return curves::isApprox<Numeric>(m_minus_i, other.m_minus_i) && curves::isApprox<Numeric>(i_, other.i_) &&
curves::isApprox<Numeric>(bin_m_i_, other.bin_m_i_);
}
/// \brief Check if actual Bernstein polynomial and other are different.
/// \param other : the other Bernstein polynomial to check.
/// \return true if the two Bernstein polynomials are different.
virtual bool operator!=(const Bern& other) const { return !(*this == other); }
/* Attributes */
......
......@@ -54,18 +54,21 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> {
/// Given the first and last point of a control points set, create the bezier curve.
/// \param PointsBegin : an iterator pointing to the first element of a control point container.
/// \param PointsEnd : an iterator pointing to the last element of a control point container.
/// \param T : upper bound of time which is between \f$[0;T]\f$ (default \f$[0;1]\f$).
/// \param T_min : lower bound of time, curve will be defined for time in [T_min, T_max].
/// \param T_max : upper bound of time, curve will be defined for time in [T_min, T_max].
/// \param mult_T : ... (default value is 1.0).
///
template <typename In>
bezier_curve(In PointsBegin, In PointsEnd, const time_t T_min = 0., const time_t T_max = 1.,
const time_t mult_T = 1.)
: T_min_(T_min),
: dim_(PointsBegin->size()),
T_min_(T_min),
T_max_(T_max),
mult_T_(mult_T),
size_(std::distance(PointsBegin, PointsEnd)),
degree_(size_ - 1),
bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_)) {
bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_))
{
if (bernstein_.size() != size_) {
throw std::invalid_argument("Invalid size of polynomial");
}
......@@ -74,41 +77,42 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> {
throw std::invalid_argument("can't create bezier min bound is higher than max bound");
}
for (; it != PointsEnd; ++it) {
if(Safe && static_cast<size_t>(it->size()) != dim_)
throw std::invalid_argument("All the control points must have the same dimension.");
control_points_.push_back(*it);
}
// set dim
if (control_points_.size() != 0) {
dim_ = PointsBegin->size();
}
}
/// \brief Constructor
/// \brief Constructor with constraints.
/// This constructor will add 4 points (2 after the first one, 2 before the last one)
/// to ensure that velocity and acceleration constraints are respected.
/// \param PointsBegin : an iterator pointing to the first element of a control point container.
/// \param PointsEnd : an iterator pointing to the last element of a control point container.
/// \param constraints : constraints applying on start / end velocities and acceleration.
/// \param T_min : lower bound of time, curve will be defined for time in [T_min, T_max].
/// \param T_max : upper bound of time, curve will be defined for time in [T_min, T_max].
/// \param mult_T : ... (default value is 1.0).
///
template <typename In>
bezier_curve(In PointsBegin, In PointsEnd, const curve_constraints_t& constraints, const time_t T_min = 0.,
const time_t T_max = 1., const time_t mult_T = 1.)
: T_min_(T_min),
: dim_(PointsBegin->size()),
T_min_(T_min),
T_max_(T_max),
mult_T_(mult_T),
size_(std::distance(PointsBegin, PointsEnd) + 4),
degree_(size_ - 1),
bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_)) {
bernstein_(curves::makeBernstein<num_t>((unsigned int)degree_))
{
if (Safe && (size_ < 1 || T_max_ <= T_min_)) {
throw std::invalid_argument("can't create bezier min bound is higher than max bound");
}
t_point_t updatedList = add_constraints<In>(PointsBegin, PointsEnd, constraints);
for (cit_point_t cit = updatedList.begin(); cit != updatedList.end(); ++cit) {
if(Safe && static_cast<size_t>(cit->size()) != dim_)
throw std::invalid_argument("All the control points must have the same dimension.");
control_points_.push_back(*cit);
}
// set dim
if (control_points_.size() != 0) {
dim_ = PointsBegin->size();
}
}
bezier_curve(const bezier_curve& other)
......@@ -148,7 +152,7 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> {
* isEquivalent
* @param other the other curve to check
* @param prec the precision treshold, default Eigen::NumTraits<Numeric>::dummy_precision()
* @return true is the two curves are approximately equals
* @return true if the two curves are approximately equals
*/
bool isApprox(const bezier_curve_t& other, const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision()) const {
bool equal = curves::isApprox<num_t>(T_min_, other.min()) && curves::isApprox<num_t>(T_max_, other.max()) &&
......@@ -339,7 +343,6 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> {
/// \brief Split the bezier curve in 2 at time t.
/// \param t : list of points.
/// \param u : unNormalized time.
/// \return pair containing the first element of both bezier curve obtained.
///
std::pair<bezier_curve_t, bezier_curve_t> split(const Numeric t) const {
......@@ -413,6 +416,10 @@ struct bezier_curve : public curve_abc<Time, Numeric, Safe, Point> {
}
private:
/// \brief Ensure constraints of bezier curve.
/// Add 4 points (2 after the first one, 2 before the last one) to biezer curve
/// to ensure that velocity and acceleration constraints are respected.
///
template <typename In>
t_point_t add_constraints(In PointsBegin, In PointsEnd, const curve_constraints_t& constraints) {
t_point_t res;
......
/**
* \file constant_curve.h
* \brief class allowing to create a constant_curve curve.
* \author Pierre Fernbach
* \version 0.4
* \date 29/04/2020
*/
#ifndef _CLASS_CONSTANTCURVE
#define _CLASS_CONSTANTCURVE
#include "curve_abc.h"
namespace curves {
/// \class constant_curve.
/// \brief Represents a constant_curve curve, always returning the same value and a null derivative
///
template <typename Time = double, typename Numeric = Time, bool Safe = false,
typename Point = Eigen::Matrix<Numeric, Eigen::Dynamic, 1>, typename Point_derivate = Point>
struct constant_curve : public curve_abc<Time, Numeric, Safe, Point, Point_derivate> {
typedef Point point_t;
typedef Point_derivate point_derivate_t;
typedef Time time_t;
typedef Numeric num_t;
typedef constant_curve<Time, Numeric, Safe, Point, Point_derivate> constant_curve_t;
typedef constant_curve<Time, Numeric, Safe, Point_derivate> curve_derivate_t;
typedef curve_abc<Time, Numeric, Safe, point_t, Point_derivate> curve_abc_t; // parent class
/* Constructors - destructors */
public:
/// \brief Empty constructor. Curve obtained this way can not perform other class functions.
///
constant_curve() : T_min_(0), T_max_(0), dim_(0) {}
/// \brief Constructor..
/// \param value : The constant value
/// \param T_min : lower bound of the time interval
/// \param T_max : upper bound of the time interval
///
constant_curve(const Point& value, const time_t T_min = 0., const time_t T_max = std::numeric_limits<time_t>::max())
: value_(value), T_min_(T_min), T_max_(T_max), dim_(value.size()) {
if (Safe && T_min_ > T_max_) {
throw std::invalid_argument("can't create constant curve: min bound is higher than max bound");
}
}
/// \brief Copy constructor
/// \param other
constant_curve(const constant_curve_t& other)
: value_(other.value_), T_min_(other.T_min_), T_max_(other.T_max_), dim_(other.dim_) {}
/// \brief Destructor.
virtual ~constant_curve() {}
/* Constructors - destructors */
/*Operations*/
/// \brief Evaluation of the cubic spline at time t.
/// \param t : time when to evaluate the spine
/// \return \f$x(t)\f$, point corresponding on curve at time t.
virtual point_t operator()(const time_t t) const {
if (Safe && (t < T_min_ || t > T_max_)) {
throw std::invalid_argument(
"error in constant curve : time t to evaluate should be in range [Tmin, Tmax] of the curve");
}
return value_;
}
/// \brief Compute the derived curve at order N.
/// Computes the derivative order N, \f$\frac{d^Nx(t)}{dt^N}\f$ of bezier curve of parametric equation x(t).
/// \param order : order of derivative.
/// \return \f$\frac{d^Nx(t)}{dt^N}\f$ derivative order N of the curve.
curve_derivate_t compute_derivate() const {
size_t derivate_size;
if (point_derivate_t::RowsAtCompileTime == Eigen::Dynamic) {
derivate_size = dim_;
} else {
derivate_size = point_derivate_t::RowsAtCompileTime;
}
point_derivate_t value(point_derivate_t::Zero(derivate_size));
return curve_derivate_t(value, T_min_, T_max_);
}
/// \brief Compute the derived curve at order N.
/// \param order : order of derivative.
/// \return A pointer to \f$\frac{d^Nx(t)}{dt^N}\f$ derivative order N of the curve.
virtual curve_derivate_t* compute_derivate_ptr(const std::size_t) const {
return new curve_derivate_t(compute_derivate());
}
/// \brief Evaluate the derivative of order N of curve at time t.
/// \param t : time when to evaluate the spline.
/// \param order : order of derivative.
/// \return \f$\frac{d^Nx(t)}{dt^N}\f$, point corresponding on derivative curve of order N at time t.
virtual point_derivate_t derivate(const time_t t, const std::size_t) const {
if (Safe && (t < T_min_ || t > T_max_)) {
throw std::invalid_argument(
"error in constant curve : time t to derivate should be in range [Tmin, Tmax] of the curve");
}
size_t derivate_size;
if (point_derivate_t::RowsAtCompileTime == Eigen::Dynamic) {
derivate_size = dim_;
} else {
derivate_size = point_derivate_t::RowsAtCompileTime;
}
return point_derivate_t::Zero(derivate_size);
}
/**
* @brief isApprox check if other and *this are approximately equals given a precision treshold
* Only two curves of the same class can be approximately equals,
* for comparison between different type of curves see isEquivalent.
* @param other the other curve to check
* @param prec the precision treshold, default Eigen::NumTraits<Numeric>::dummy_precision()
* @return true is the two curves are approximately equals
*/
virtual bool isApprox(const constant_curve_t& other,
const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision()) const {
return curves::isApprox<num_t>(T_min_, other.min()) && curves::isApprox<num_t>(T_max_, other.max()) &&
dim_ == other.dim() && value_.isApprox(other.value_, prec);
}
virtual bool isApprox(const curve_abc_t* other,
const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision()) const {
const constant_curve_t* other_cast = dynamic_cast<const constant_curve_t*>(other);
if (other_cast)
return isApprox(*other_cast, prec);
else
return false;
}
virtual bool operator==(const constant_curve_t& other) const { return isApprox(other); }
virtual bool operator!=(const constant_curve_t& other) const { return !(*this == other); }
/*Helpers*/
/// \brief Get dimension of curve.
/// \return dimension of curve.
std::size_t virtual dim() const { return dim_; }
/// \brief Get the minimum time for which the curve is defined
/// \return \f$t_{min}\f$ lower bound of time range.
num_t virtual min() const { return T_min_; }
/// \brief Get the maximum time for which the curve is defined.
/// \return \f$t_{max}\f$ upper bound of time range.
num_t virtual max() const { return T_max_; }
/// \brief Get the degree of the curve.
/// \return \f$degree\f$, the degree of the curve.
virtual std::size_t degree() const { return 0; }
/*Helpers*/
/*Attributes*/
Point value_;
time_t T_min_, T_max_; // const
std::size_t dim_; // const
/*Attributes*/
// Serialization of the class
friend class boost::serialization::access;
template <class Archive>
void serialize(Archive& ar, const unsigned int version) {
if (version) {
// Do something depending on version ?
}
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
ar& boost::serialization::make_nvp("value", value_);
ar& boost::serialization::make_nvp("T_min", T_min_);
ar& boost::serialization::make_nvp("T_max", T_max_);
ar& boost::serialization::make_nvp("dim", dim_);
}
}; // struct constant_curve
} // namespace curves
#endif // _CLASS_CONSTANTCURVE
This diff is collapsed.
/**
* \file cubic_spline.h
* \brief Definition of a cubic spline.
* \author Steve T.
* \version 0.1
* \date 06/17/2013
*
* This file contains definitions for the CubicFunction struct.
* It allows the creation and evaluation of natural
* smooth cubic splines of arbitrary dimension
*/
#ifndef _STRUCT_CUBICSPLINE
#define _STRUCT_CUBICSPLINE
#include "MathDefs.h"
#include "polynomial.h"
#include <stdexcept>
namespace curves {
/// \brief Creates coefficient vector of a cubic spline defined on the interval
/// \f$[t_{min}, t_{max}]\f$. It follows the equation : <br>
/// \f$ x(t) = a + b(t - t_{min}) + c(t - t_{min})^2 + d(t - t_{min})^3 \f$ where \f$ t \in [t_{min}, t_{max}] \f$
/// with a, b, c and d the control points.
///
template <typename Point, typename T_Point>
T_Point make_cubic_vector(Point const& a, Point const& b, Point const& c, Point const& d) {
T_Point res;
res.push_back(a);
res.push_back(b);
res.push_back(c);
res.push_back(d);
return res;
}
template <typename Time, typename Numeric, bool Safe, typename Point, typename T_Point>
polynomial<Time, Numeric, Safe, Point, T_Point> create_cubic(Point const& a, Point const& b, Point const& c,
Point const& d, const Time t_min, const Time t_max) {
T_Point coeffs = make_cubic_vector<Point, T_Point>(a, b, c, d);
return polynomial<Time, Numeric, Safe, Point, T_Point>(coeffs.begin(), coeffs.end(), t_min, t_max);
}
} // namespace curves
#endif //_STRUCT_CUBICSPLINE
......@@ -37,6 +37,7 @@ struct curve_abc : std::unary_function<Time, Point>, public serialization::Seria
typedef Time time_t;
typedef Numeric num_t;
typedef curve_abc<Time, Numeric, Safe, point_t, point_derivate_t> 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;
/* Constructors - destructors */
......@@ -57,7 +58,7 @@ struct curve_abc : std::unary_function<Time, Point>, public serialization::Seria
/// \brief Compute the derived curve at order N.
/// \param order : order of derivative.
/// \return A pointer to \f$\frac{d^Nx(t)}{dt^N}\f$ derivative order N of the curve.
virtual curve_t* compute_derivate_ptr(const std::size_t order) const = 0;
virtual curve_derivate_t* compute_derivate_ptr(const std::size_t order) const = 0;
/// \brief Evaluate the derivative of order N of curve at time t.
/// \param t : time when to evaluate the spline.
......@@ -71,7 +72,7 @@ struct curve_abc : std::unary_function<Time, Point>, public serialization::Seria
* @param other the other curve to check
* @param order the order up to which the derivatives of the curves are checked for equality
* @param prec the precision treshold, default Eigen::NumTraits<Numeric>::dummy_precision()
* @return true is the two curves are approximately equals
* @return true if the two curves are approximately equal
*/
bool isEquivalent(const curve_t* other, const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision(),
const size_t order = 5) const {
......@@ -89,7 +90,7 @@ struct curve_abc : std::unary_function<Time, Point>, public serialization::Seria
}
t += inc;
}
// check if the derivatives are equals
// check if the derivatives are equal
for (size_t n = 1; n <= order; ++n) {
t = min();
while (t <= max()) {
......@@ -103,12 +104,12 @@ struct curve_abc : std::unary_function<Time, Point>, public serialization::Seria
}
/**
* @brief isApprox check if other and *this are approximately equals given a precision treshold
* Only two curves of the same class can be approximately equals,
* @brief isApprox check if other and *this are approximately equal given a precision treshold
* Only two curves of the same class can be approximately equal,
* for comparison between different type of curves see isEquivalent.
* @param other the other curve to check
* @param prec the precision treshold, default Eigen::NumTraits<Numeric>::dummy_precision()
* @return true is the two curves are approximately equals
* @return true if the two curves are approximately equal
*/
virtual bool isApprox(const curve_t* other,
const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision()) const = 0;
......
......@@ -36,6 +36,8 @@ Polynomial polynomial_from_curve(const typename Polynomial::curve_abc_t& curve)
/// \return the equivalent cubic bezier curve.
template <typename Bezier>
Bezier bezier_from_curve(const typename Bezier::curve_abc_t& curve) {
if(curve.degree() > 3)
throw std::invalid_argument("bezier_from_curve is only implemented for curves of degree <= 3.");
typedef typename Bezier::point_t point_t;
typedef typename Bezier::t_point_t t_point_t;
typedef typename Bezier::num_t num_t;
......@@ -68,6 +70,8 @@ Bezier bezier_from_curve(const typename Bezier::curve_abc_t& curve) {
/// \return the equivalent cubic hermite spline.
template <typename Hermite>
Hermite hermite_from_curve(const typename Hermite::curve_abc_t& curve) {
if(curve.degree() > 3)
throw std::invalid_argument("hermite_from_curve is only implemented for curves of degree <= 3.");
typedef typename Hermite::pair_point_tangent_t pair_point_tangent_t;
typedef typename Hermite::t_pair_point_tangent_t t_pair_point_tangent_t;
typedef typename Hermite::point_t point_t;
......@@ -91,4 +95,4 @@ Hermite hermite_from_curve(const typename Hermite::curve_abc_t& curve) {
return Hermite(control_points.begin(), control_points.end(), time_control_points);
}
} // namespace curves
#endif //_CLASS_CURVE_CONVERSION
\ No newline at end of file
#endif //_CLASS_CURVE_CONVERSION
......@@ -20,10 +20,9 @@
#define _CLASS_EXACTCUBIC
#include "curve_abc.h"
#include "cubic_spline.h"
#include "quintic_spline.h"
#include "curve_constraint.h"
#include "piecewise_curve.h"
#include "polynomial.h"
#include "MathDefs.h"
......@@ -41,6 +40,7 @@ template <typename Time = double, typename Numeric = Time, bool Safe = false,
typename SplineBase = polynomial<Time, Numeric, Safe, Point, T_Point> >
struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point> {
typedef Point point_t;
typedef const Eigen::Ref<const point_t> point_ref_t;
typedef T_Point t_point_t;
typedef Eigen::Matrix<Numeric, Eigen::Dynamic, Eigen::Dynamic> MatrixX;
typedef Eigen::Matrix<Numeric, 3, 3> Matrix3;
......@@ -52,9 +52,10 @@ struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point> {
typedef typename t_spline_t::const_iterator cit_spline_t;
typedef curve_constraints<Point> spline_constraints;
typedef exact_cubic<Time, Numeric, Safe, Point, T_Point, SplineBase> exact_cubic_t;
typedef exact_cubic<Time, Numeric, Safe, point_t, T_Point, SplineBase> exact_cubic_t;
typedef curve_abc<Time, Numeric, Safe, point_t> curve_abc_t; // parent class
typedef piecewise_curve<Time, Numeric, Safe, Point> piecewise_curve_t;
typedef piecewise_curve<Time, Numeric, Safe, point_t> piecewise_curve_t;
typedef polynomial<Time, Numeric, Safe, point_t> polynomial_t;
typedef typename piecewise_curve_t::t_curve_ptr_t t_curve_ptr_t;
/* Constructors - destructors */
......@@ -128,6 +129,29 @@ struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point> {
}
private:
static polynomial_t create_cubic(point_ref_t a,point_ref_t b, point_ref_t c, point_ref_t d,
const time_t t_min, const time_t t_max){
typename polynomial_t::t_point_t coeffs;
coeffs.push_back(a);
coeffs.push_back(b);
coeffs.push_back(c);
coeffs.push_back(d);
return polynomial_t(coeffs.begin(), coeffs.end(), t_min, t_max);
}
static polynomial_t create_quintic(point_ref_t a,point_ref_t b, point_ref_t c, point_ref_t d,
point_ref_t e, point_ref_t f,
const time_t t_min, const time_t t_max){
typename polynomial_t::t_point_t coeffs;
coeffs.push_back(a);
coeffs.push_back(b);
coeffs.push_back(c);
coeffs.push_back(d);
coeffs.push_back(e);
coeffs.push_back(f);
return polynomial_t(coeffs.begin(), coeffs.end(), t_min, t_max);
}
/// \brief Compute polynom of exact cubic spline from waypoints.
/// Compute the coefficients of polynom as in paper : "Task-Space Trajectories via Cubic Spline Optimization".<br>
/// \f$x_i(t)=a_i+b_i(t-t_i)+c_i(t-t_i)^2\f$<br>
......@@ -198,7 +222,7 @@ struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point> {
it = wayPointsBegin, next = wayPointsBegin;
++next;
for (int i = 0; next != wayPointsEnd; ++i, ++it, ++next) {
subSplines.push_back(create_cubic<Time, Numeric, Safe, Point, T_Point>(a.row(i), b.row(i), c.row(i), d.row(i),
subSplines.push_back(create_cubic(a.row(i), b.row(i), c.row(i), d.row(i),
(*it).first, (*next).first));
}
return subSplines;
......@@ -230,7 +254,7 @@ struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point> {
const num_t &init_t = wayPointsBegin->first, end_t = wayPointsNext->first;
const num_t dt = end_t - init_t, dt_2 = dt * dt, dt_3 = dt_2 * dt;
const point_t d0 = (a1 - a0 - b0 * dt - c0 * dt_2) / dt_3;
subSplines.push_back(create_cubic<Time, Numeric, Safe, Point, T_Point>(a0, b0, c0, d0, init_t, end_t));
subSplines.push_back(create_cubic(a0, b0, c0, d0, init_t, end_t));
constraints.init_vel = subSplines.back().derivate(end_t, 1);
constraints.init_acc = subSplines.back().derivate(end_t, 2);
}
......@@ -270,7 +294,7 @@ struct exact_cubic : public piecewise_curve<Time, Numeric, Safe, Point> {
d = rhs.row(0);
e = rhs.row(1);
f = rhs.row(2);
subSplines.push_back(create_quintic<Time, Numeric, Safe, Point, T_Point>(a0, b0, c0, d, e, f, init_t, end_t));
subSplines.push_back(create_quintic(a0, b0, c0, d, e, f, init_t, end_t));
}
public:
......
......@@ -21,6 +21,9 @@ struct curve_abc;
template <typename Time, typename Numeric, bool Safe, typename Point>
struct bezier_curve;
template <typename Time, typename Numeric, bool Safe, typename Point,typename Point_derivate>
struct constant_curve;
template <typename Time, typename Numeric, bool Safe, typename Point>
struct cubic_hermite_spline;
......@@ -36,6 +39,9 @@ struct polynomial;
template <typename Time, typename Numeric, bool Safe>
struct SE3Curve;
template <typename Time, typename Numeric, bool Safe, typename Point>
struct sinusoidal;
template <typename Time, typename Numeric, bool Safe>
struct SO3Linear;
......@@ -81,13 +87,16 @@ typedef boost::shared_ptr<curve_SE3_t> curve_SE3_ptr_t;
typedef polynomial<double, double, true, pointX_t, t_pointX_t> polynomial_t;
typedef exact_cubic<double, double, true, pointX_t, t_pointX_t, polynomial_t> exact_cubic_t;
typedef bezier_curve<double, double, true, pointX_t> bezier_t;
typedef constant_curve<double, double, true, pointX_t, pointX_t> constant_t;
typedef cubic_hermite_spline<double, double, true, pointX_t> cubic_hermite_spline_t;
typedef piecewise_curve<double, double, true, pointX_t, pointX_t, curve_abc_t> piecewise_t;
typedef sinusoidal<double, double, true, pointX_t> sinusoidal_t;
// definition of all curves class with point3 as return type:
typedef polynomial<double, double, true, point3_t, t_point3_t> polynomial3_t;
typedef exact_cubic<double, double, true, point3_t, t_point3_t, polynomial_t> exact_cubic3_t;
typedef bezier_curve<double, double, true, point3_t> bezier3_t;
typedef constant_curve<double, double, true, point3_t, point3_t> constant3_t;
typedef cubic_hermite_spline<double, double, true, point3_t> cubic_hermite_spline3_t;
typedef piecewise_curve<double, double, true, point3_t, point3_t, curve_3_t> piecewise3_t;
......
......@@ -119,8 +119,14 @@ class rotation_spline : public curve_abc_quat_t {
return exact_cubic_constraint_one_dim(waypoints.begin(), waypoints.end());
}
/// \brief Get dimension of curve.
/// \return dimension of curve.
virtual std::size_t dim() const { return dim_; }
/// \brief Get the minimum time for which the curve is defined.
/// \return \f$t_{min}\f$, lower bound of time range.
virtual time_t min() const { return min_; }
/// \brief Get the maximum time for which the curve is defined.
/// \return \f$t_{max}\f$, upper bound of time range.
virtual time_t max() const { return max_; }
/// \brief Get the degree of the curve.
/// \return \f$degree\f$, the degree of the curve.
......
......@@ -32,7 +32,10 @@ struct linear_variable : public serialization::Serializable {
linear_variable(const vector_x_t& c) : B_(matrix_x_t::Zero(c.size(), c.size())), c_(c), zero(false) {} // constant
linear_variable(const matrix_x_t& B, const vector_x_t& c) : B_(B), c_(c), zero(false) {} // mixed
// linear evaluation
/// \brief Linear evaluation for vector x.
/// \param val : vector to evaluate the linear variable.
/// \return Evaluation of linear variable for vector x.
///
vector_x_t operator()(const Eigen::Ref<const vector_x_t>& val) const {
if (isZero()) return c();
if (Safe && B().cols() != val.rows())
......@@ -40,6 +43,10 @@ struct linear_variable : public serialization::Serializable {
return B() * val + c();
}
/// \brief Add another linear variable.
/// \param w1 : linear variable to add.
/// \return Linear variable after operation.
///
linear_variable_t& operator+=(const linear_variable_t& w1) {
if (w1.isZero()) return *this;
if (isZero()) {
......@@ -51,6 +58,11 @@ struct linear_variable : public serialization::Serializable {
this->c_ += w1.c_;
return *this;
}
/// \brief Substract another linear variable.
/// \param w1 : linear variable to substract.
/// \return Linear variable after operation.
///
linear_variable_t& operator-=(const linear_variable_t& w1) {
if (w1.isZero()) return *this;
if (isZero()) {
......@@ -62,25 +74,48 @@ struct linear_variable : public serialization::Serializable {
this->c_ -= w1.c_;
return *this;
}
/// \brief Divide by a constant : p_i / d = B_i*x/d + c_i/d.
/// \param d : constant.
/// \return Linear variable after operation.
///
linear_variable_t& operator/=(const double d) {
B_ /= d;
c_ /= d;
return *this;
}
/// \brief Multiply by a constant : p_i / d = B_i*x*d + c_i*d.
/// \param d : constant.
/// \return Linear variable after operation.
///
linear_variable_t& operator*=(const double d) {
B_ *= d;
c_ *= d;
return *this;
}
/// \brief Get a linear variable equal to zero.
/// \param dim : Dimension of linear variable.
/// \return Linear variable equal to zero.
///
static linear_variable_t Zero(size_t dim = 0) {
return linear_variable_t(matrix_x_t::Identity(dim, dim), vector_x_t::Zero(dim));
}
/// \brief Get dimension of linear variable.
/// \return Dimension of linear variable.
///
std::size_t size() const { return zero ? 0 : std::max(B_.cols(), c_.size()); }
/// \brief Get norm of linear variable (Norm of B plus norm of C).
/// \return Norm of linear variable.
Numeric norm() const { return isZero() ? 0 : (B_.norm() + c_.norm()); }
/// \brief Check if actual linear variable and other are approximately equal given a precision treshold.
/// Only two curves of the same class can be approximately equal,
/// \param prec : the precision treshold, default Eigen::NumTraits<Numeric>::dummy_precision()
/// \return true if the two linear variables are approximately equal.
bool isApprox(const linear_variable_t& other,
const double prec = Eigen::NumTraits<Numeric>::dummy_precision()) const {
return (*this - other).norm() < prec;
......
This diff is collapsed.
This diff is collapsed.
......@@ -224,6 +224,35 @@ struct polynomial : public curve_abc<Time, Numeric, Safe, Point> {
// polynomial& operator=(const polynomial& other);
/**
* @brief MinimumJerk Build a polynomial curve connecting p_init to p_final minimizing the time integral of the
* squared jerk with a zero initial and final velocity and acceleration
* @param p_init the initial point
* @param p_final the final point
* @param t_min initial time
* @param t_max final time
* @return the polynomial curve
*/
static polynomial_t MinimumJerk(const point_t& p_init, const point_t& p_final, const time_t t_min = 0.,
const time_t t_max = 1.) {
if (t_min > t_max) throw std::invalid_argument("final time should be superior or equal to initial time.");
const size_t dim(p_init.size());
if (static_cast<size_t>(p_final.size()) != dim)
throw std::invalid_argument("Initial and final points must have the same dimension.");
const double T = t_max - t_min;
const double T2 = T * T;
const double T3 = T2 * T;
const double T4 = T3 * T;
const double T5 = T4 * T;
coeff_t coeffs = coeff_t::Zero(dim, 6); // init coefficient matrix with the right size
coeffs.col(0) = p_init;
coeffs.col(3) = 10 * (p_final - p_init) / T3;
coeffs.col(4) = -15 * (p_final - p_init) / T4;
coeffs.col(5) = 6 * (p_final - p_init) / T5;
return polynomial_t(coeffs, t_min, t_max);
}
private:
void safe_check() {
if (Safe) {
......
/**
* \file cubic_spline.h
* \brief Definition of a cubic spline.
* \author Steve T.
* \version 0.1
* \date 06/17/2013
*
* This file contains definitions for the CubicFunction struct.
* It allows the creation and evaluation of natural
* smooth cubic splines of arbitrary dimension
*/
#ifndef _STRUCT_QUINTIC_SPLINE
#define _STRUCT_QUINTIC_SPLINE
#include "MathDefs.h"
#include "polynomial.h"
#include <stdexcept>
namespace curves {
/// \brief Creates coefficient vector of a quintic spline defined on the interval
/// \f$[t_{min}, t_{max}]\f$. It follows the equation :<br>
/// \f$ x(t) = a + b(t - t_{min}) + c(t - t_{min})^2 + d(t - t_{min})^3 + e(t - t_{min})^4 + f(t - t_{min})^5 \f$ <br>
/// where \f$ t \in [t_{min}, t_{max}] \f$.
///
template <typename Point, typename T_Point>
T_Point make_quintic_vector(Point const& a, Point const& b, Point const& c, Point const& d, Point const& e,
Point const& f) {
T_Point res;
res.push_back(a);
res.push_back(b);
res.push_back(c);
res.push_back(d);
res.push_back(e);
res.push_back(f);
return res;
}
template <typename Time, typename Numeric, bool Safe, typename Point, typename T_Point>
polynomial<Time, Numeric, Safe, Point, T_Point> create_quintic(Point const& a, Point const& b, Point const& c,
Point const& d, Point const& e, Point const& f,
const Time t_min, const Time t_max) {
T_Point coeffs = make_quintic_vector<Point, T_Point>(a, b, c, d, e, f);
return polynomial<Time, Numeric, Safe, Point, T_Point>(coeffs.begin(), coeffs.end(), t_min, t_max);
}
} // namespace curves
#endif //_STRUCT_QUINTIC_SPLINE
......@@ -28,6 +28,7 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
typedef Eigen::Quaternion<Scalar> Quaternion;
typedef Time time_t;
typedef curve_abc<Time, Numeric, Safe, point_t, point_derivate_t> curve_abc_t; // parent class
typedef polynomial<Time, Numeric, Safe, point_derivate_t> curve_derivate_t;
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)
......@@ -190,14 +191,14 @@ struct SE3Curve : public curve_abc<Time, Numeric, Safe, Eigen::Transform<Numeric
return res;
}
SE3Curve_t compute_derivate(const std::size_t /*order*/) const {
curve_derivate_t compute_derivate(const std::size_t /*order*/) const {
throw std::logic_error("Compute derivate for SE3 is not implemented yet.");
}
/// \brief Compute the derived curve at order N.
/// \param order : order of derivative.
/// \return A pointer to \f$\frac{d^Nx(t)}{dt^N}\f$ derivative order N of the curve.
SE3Curve_t* compute_derivate_ptr(const std::size_t order) const { return new SE3Curve_t(compute_derivate(order)); }
curve_derivate_t* compute_derivate_ptr(const std::size_t order) const { return new curve_derivate_t(compute_derivate(order)); }
/*Helpers*/
/// \brief Get dimension of curve.
......
......@@ -16,8 +16,10 @@
#include "curves/curve_abc.h"
#include "curves/so3_linear.h"
#include "curves/se3_curve.h"
#include "curves/sinusoidal.h"
#include "curves/polynomial.h"
#include "curves/bezier_curve.h"
#include "curves/constant_curve.h"
#include "curves/piecewise_curve.h"
#include "curves/exact_cubic.h"
#include "curves/cubic_hermite_spline.h"
......
......@@ -35,15 +35,18 @@ void register_types(Archive& ar) {
ar.template register_type<polynomial_t>();
ar.template register_type<exact_cubic_t>();
ar.template register_type<bezier_t>();
ar.template register_type<constant_t>();
ar.template register_type<cubic_hermite_spline_t>();
ar.template register_type<piecewise_t>();
ar.template register_type<polynomial3_t>();
ar.template register_type<exact_cubic3_t>();
ar.template register_type<bezier3_t>();
ar.template register_type<constant3_t>();
ar.template register_type<cubic_hermite_spline3_t>();
ar.template register_type<piecewise3_t>();
ar.template register_type<SO3Linear_t>();
ar.template register_type<SE3Curve_t>();
ar.template register_type<sinusoidal_t>();
ar.template register_type<piecewise_SE3_t>();
}
......
/**
* \file sinusoidal.h
* \brief class allowing to create a sinusoidal curve.
* \author Pierre Fernbach
* \version 0.4
* \date 29/04/2020
*/
#ifndef _CLASS_SINUSOIDALCURVE
#define _CLASS_SINUSOIDALCURVE
#include "curve_abc.h"
#include <cmath>
namespace curves {
/// \class sinusoidal.
/// \brief Represents a sinusoidal curve, evaluating the following equation:
/// p0 + amplitude * (sin(2pi/T + phi)
///
template <typename Time = double, typename Numeric = Time, bool Safe = false,
typename Point = Eigen::Matrix<Numeric, Eigen::Dynamic, 1> >
struct sinusoidal : public curve_abc<Time, Numeric, Safe, Point> {
typedef Point point_t;
typedef Point point_derivate_t;
typedef Time time_t;
typedef Numeric num_t;
typedef sinusoidal<Time, Numeric, Safe, Point> sinusoidal_t;
typedef curve_abc<Time, Numeric, Safe, Point> curve_abc_t; // parent class
/* Constructors - destructors */
public:
/// \brief Empty constructor. Curve obtained this way can not perform other class functions.
///
sinusoidal() : T_min_(0), T_max_(0), dim_(0) {}
/// \brief Constructor
/// \param p0 : Offset of the sinusoidal
/// \param amplitude: Amplitude
/// \param T : The period
/// \param phi : the phase
/// \param T_min : lower bound of the time interval (default to 0)
/// \param T_max : upper bound of the time interval (default to +inf)
///
sinusoidal(const Point& p0, const Point& amplitude, const time_t T, const time_t phi, const time_t T_min = 0.,
const time_t T_max = std::numeric_limits<time_t>::max())
: p0_(p0),
amplitude_(amplitude),
T_(T),
phi_(std::fmod(phi, 2. * M_PI)),
T_min_(T_min),
T_max_(T_max),
dim_(p0_.size()) {
if (Safe && T_min_ > T_max_) {
throw std::invalid_argument("can't create constant curve: min bound is higher than max bound");
}
if (T_ <= 0.) throw std::invalid_argument("The period must be strictly positive");
if (static_cast<size_t>(amplitude_.size()) != dim_)
throw std::invalid_argument("The offset and the amplitude must have the same dimension");
}
/// \brief Constructor from stationary points
/// \param traj_time: duration to go from p_init to p_final (half a period)
/// \param p_init : first stationary point, either minimum or maximum
/// \param p_final : second stationary point, either minimum or maximum
/// \param T_min : lower bound of the time interval (default to 0)
/// \param T_max : upper bound of the time interval (default to +inf)
///
sinusoidal(const time_t traj_time, const Point& p_init, const Point& p_final, const time_t T_min = 0.,
const time_t T_max = std::numeric_limits<time_t>::max())
: T_(2. * traj_time), phi_(M_PI / 2.), T_min_(T_min), T_max_(T_max), dim_(p_init.size()) {
if (Safe && T_min_ > T_max_) {
throw std::invalid_argument("can't create constant curve: min bound is higher than max bound");
}
if (T_ <= 0) throw std::invalid_argument("The period must be strictly positive");
if (p_init.size() != p_final.size())
throw std::invalid_argument("The two stationary points must have the same dimension");
p0_ = (p_init + p_final) / 2.;
amplitude_ = (p_init - p_final) / 2.;
}
/// \brief Copy constructor
/// \param other
sinusoidal(const sinusoidal_t& other)
: p0_(other.p0_),
amplitude_(other.amplitude_),
T_(other.T_),
phi_(other.phi_),
T_min_(other.T_min_),
T_max_(other.T_max_),
dim_(other.dim_) {}
/// \brief Destructor.
virtual ~sinusoidal() {}
/* Constructors - destructors */
/*Operations*/
/// \brief Evaluation of the cubic spline at time t.
/// \param t : time when to evaluate the spine
/// \return \f$x(t)\f$, point corresponding on curve at time t.
virtual point_t operator()(const time_t t) const {
if (Safe && (t < T_min_ || t > T_max_)) {
throw std::invalid_argument(
"error in sinusoidal curve : time t to evaluate should be in range [Tmin, Tmax] of the curve");
}
return p0_ + amplitude_ * sin(two_pi_f(t) + phi_);
}
/// \brief Evaluate the derivative of order N of curve at time t.
/// \param t : time when to evaluate the spline.
/// \param order : order of derivative.
/// \return \f$\frac{d^Nx(t)}{dt^N}\f$, point corresponding on derivative curve of order N at time t.
virtual point_derivate_t derivate(const time_t t, const std::size_t order) const {
if (Safe && (t < T_min_ || t > T_max_)) {
throw std::invalid_argument(
"error in constant curve : time t to derivate should be in range [Tmin, Tmax] of the curve");
}
if (order <= 0) throw std::invalid_argument("Order must be strictly positive");
return amplitude_ * pow(2. * M_PI / T_, static_cast<num_t>(order)) *
sin(two_pi_f(t) + phi_ + (M_PI * static_cast<num_t>(order) / 2.));
}
/// \brief Compute the derived curve at order N.
/// Computes the derivative order N, \f$\frac{d^Nx(t)}{dt^N}\f$ of bezier curve of parametric equation x(t).
/// \param order : order of derivative.
/// \return \f$\frac{d^Nx(t)}{dt^N}\f$ derivative order N of the curve.
sinusoidal_t compute_derivate(const std::size_t order) const {
if (order <= 0) throw std::invalid_argument("Order must be strictly positive");
const point_t amplitude = amplitude_ * pow(2. * M_PI / T_, static_cast<num_t>(order));
const time_t phi = phi_ + (M_PI * static_cast<num_t>(order) / 2.);
return sinusoidal_t(point_t::Zero(dim_), amplitude, T_, phi, T_min_, T_max_);
}
/// \brief Compute the derived curve at orderN.
/// \param order : order of derivative.
/// \return A pointer to \f$\frac{d^Nx(t)}{dt^N}\f$ derivative order N of the curve.
virtual sinusoidal_t* compute_derivate_ptr(const std::size_t order) const {
return new sinusoidal_t(compute_derivate(order));
}
/**
* @brief isApprox check if other and *this are approximately equals given a precision treshold
* Only two curves of the same class can be approximately equals,
* for comparison between different type of curves see isEquivalent.
* @param other the other curve to check
* @param prec the precision treshold, default Eigen::NumTraits<Numeric>::dummy_precision()
* @return true is the two curves are approximately equals
*/
virtual bool isApprox(const sinusoidal_t& other,
const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision()) const {
return curves::isApprox<time_t>(T_min_, other.min()) && curves::isApprox<time_t>(T_max_, other.max()) &&
dim_ == other.dim() && p0_.isApprox(other.p0_, prec) && amplitude_.isApprox(other.amplitude_, prec) &&
curves::isApprox<time_t>(T_, other.T_) && curves::isApprox<time_t>(phi_, other.phi_);
}
virtual bool isApprox(const curve_abc_t* other,
const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision()) const {
const sinusoidal_t* other_cast = dynamic_cast<const sinusoidal_t*>(other);
if (other_cast)
return isApprox(*other_cast, prec);
else
return false;
}
virtual bool operator==(const sinusoidal_t& other) const { return isApprox(other); }
virtual bool operator!=(const sinusoidal_t& other) const { return !(*this == other); }
/*Helpers*/
/// \brief Get dimension of curve.
/// \return dimension of curve.
std::size_t virtual dim() const { return dim_; }
/// \brief Get the minimum time for which the curve is defined
/// \return \f$t_{min}\f$ lower bound of time range.
num_t virtual min() const { return T_min_; }
/// \brief Get the maximum time for which the curve is defined.
/// \return \f$t_{max}\f$ upper bound of time range.
num_t virtual max() const { return T_max_; }
/// \brief Get the degree of the curve.
/// \return \f$degree\f$, the degree of the curve.
virtual std::size_t degree() const { return 1; }
/*Helpers*/
/*Attributes*/
Point p0_; // offset
Point amplitude_;
time_t T_; // period
time_t phi_; // phase
time_t T_min_, T_max_; // const
std::size_t dim_; // const
/*Attributes*/
// Serialization of the class
friend class boost::serialization::access;
template <class Archive>
void serialize(Archive& ar, const unsigned int version) {
if (version) {
// Do something depending on version ?
}
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(curve_abc_t);
ar& boost::serialization::make_nvp("p0", p0_);
ar& boost::serialization::make_nvp("amplitude_", amplitude_);
ar& boost::serialization::make_nvp("T_", T_);
ar& boost::serialization::make_nvp("phi_", phi_);
ar& boost::serialization::make_nvp("T_min", T_min_);
ar& boost::serialization::make_nvp("T_max", T_max_);
ar& boost::serialization::make_nvp("dim", dim_);
}
private:
inline const num_t two_pi_f(const time_t& t) const { return (2 * M_PI / T_) * t; }
}; // struct sinusoidal
} // namespace curves
#endif // _CLASS_SINUSOIDALCURVE
......@@ -4,6 +4,7 @@
#include "MathDefs.h"
#include "curve_abc.h"
#include "constant_curve.h"
#include <Eigen/Geometry>
#include <boost/math/constants/constants.hpp>
......@@ -24,8 +25,10 @@ struct SO3Linear : public curve_abc<Time, Numeric, Safe, matrix3_t, point3_t > {
typedef Eigen::Quaternion<Scalar> quaternion_t;
typedef Time time_t;
typedef curve_abc<Time, Numeric, Safe, point_t, point_derivate_t> curve_abc_t;
typedef constant_curve<Time, Numeric, Safe, point_derivate_t> curve_derivate_t;
typedef SO3Linear<Time, Numeric, Safe> SO3Linear_t;
public:
/* Constructors - destructors */
/// \brief Empty constructor. Curve obtained this way can not perform other class functions.
......@@ -161,14 +164,14 @@ struct SO3Linear : public curve_abc<Time, Numeric, Safe, matrix3_t, point3_t > {
}
}
SO3Linear_t compute_derivate(const std::size_t /*order*/) const {
throw std::logic_error("Compute derivate for SO3Linear is not implemented yet.");
curve_derivate_t compute_derivate(const std::size_t order) const {
return curve_derivate_t(derivate(T_min_, order), T_min_, T_max_);
}
/// \brief Compute the derived curve at order N.
/// \param order : order of derivative.
/// \return A pointer to \f$\frac{d^Nx(t)}{dt^N}\f$ derivative order N of the curve.
SO3Linear_t* compute_derivate_ptr(const std::size_t order) const { return new SO3Linear_t(compute_derivate(order)); }
curve_derivate_t* compute_derivate_ptr(const std::size_t order) const { return new curve_derivate_t(compute_derivate(order)); }
/*Helpers*/
/// \brief Get dimension of curve.
......
......@@ -5,5 +5,9 @@ PYTHON_INSTALL_ON_SITE(${PROJECT_NAME} plot.py)
PYTHON_INSTALL_ON_SITE(${PROJECT_NAME} optimization.py)
ADD_PYTHON_UNIT_TEST("python-curves" "python/test/test.py" "python")
ADD_PYTHON_UNIT_TEST("python-constant" "python/test/test-constant.py" "python")
ADD_PYTHON_UNIT_TEST("python-sinusoidal" "python/test/test-sinusoidal.py" "python")
ADD_PYTHON_UNIT_TEST("python-minjerk" "python/test/test-minjerk.py" "python")
ADD_PYTHON_UNIT_TEST("python-optimization" "python/test/optimization.py" "python")
ADD_PYTHON_UNIT_TEST("python-notebook" "python/test/notebook.py" "python")
ADD_PYTHON_UNIT_TEST("python-registration" "python/test/registration.py" "python")
This diff is collapsed.
#include "curves/fwd.h"
#include "curves/linear_variable.h"
#include "curves/bezier_curve.h"
#include "curves/constant_curve.h"
#include "curves/polynomial.h"
#include "curves/exact_cubic.h"
#include "curves/curve_constraint.h"
......@@ -10,6 +11,7 @@
#include "curves/piecewise_curve.h"
#include "curves/so3_linear.h"
#include "curves/se3_curve.h"
#include "curves/sinusoidal.h"
#include "curves/python/python_definitions.h"
#include <eigenpy/memory.hpp>
#include <eigenpy/eigenpy.hpp>
......@@ -71,15 +73,18 @@ EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::matrix_pair)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::polynomial_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::exact_cubic_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::bezier_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::constant_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::cubic_hermite_spline_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::piecewise_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::polynomial3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::exact_cubic3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::bezier3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::constant3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::cubic_hermite_spline3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::piecewise3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::SO3Linear_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::SE3Curve_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::sinusoidal_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::piecewise_SE3_t)
#endif //_VARIABLES_PYTHON_BINDINGS
import unittest
class TestRegistration(unittest.TestCase):
"""Check registration incompatibilities.
ref https://github.com/stack-of-tasks/eigenpy/issues/83
ref https://gitlab.laas.fr/loco-3d/curves/-/issues/6
"""
def test_pinocchio_then_curves(self):
import pinocchio
import curves
self.assertTrue(hasattr(pinocchio, 'Quaternion'))
self.assertTrue(hasattr(curves, 'Quaternion'))
def test_curves_then_pinocchio(self):
import curves
import pinocchio
self.assertTrue(hasattr(pinocchio, 'Quaternion'))
self.assertTrue(hasattr(curves, 'Quaternion'))
if __name__ == '__main__':
unittest.main()
# Copyright (c) 2020, CNRS
# Authors: Pierre Fernbach <pfernbac@laas.fr>
import unittest
import curves
from curves import constant, constant3
import numpy as np
from numpy import array, isclose, array_equal
class ConstantCurveTest(unittest.TestCase):
def test_constructor(self):
# default constructor
c = constant()
self.assertEqual(c.min(), 0.)
self.assertEqual(c.max(), 0)
self.assertEqual(c.dim(), 0)
self.assertEqual(c.degree(), 0)
# constructor from a point
p = array([1, 23., 5., 9, -5])
c = constant(p)
self.assertEqual(c.min(), 0.)
self.assertTrue(c.max() > 1e100) # convert std::numeric_limits<time_t>::max() to python ?
self.assertEqual(c.dim(), 5)
self.assertEqual(c.degree(), 0)
# constructor with timing
c = constant(p, 1., 5.)
self.assertEqual(c.min(), 1.)
self.assertEqual(c.max(), 5.)
self.assertEqual(c.dim(), 5)
self.assertEqual(c.degree(), 0)
with self.assertRaises(ValueError):
c = constant(p, 2., 1.)
def test_evaluate(self):
p = array([1, 23., 5., 9, -5])
c = constant(p, 1., 3.)
self.assertTrue(array_equal(c(1.), p))
self.assertTrue(array_equal(c(2.5), p))
self.assertTrue(array_equal(c(3.), p))
with self.assertRaises(ValueError):
c(0.5)
with self.assertRaises(ValueError):
c(4.)
def test_derivate(self):
p = array([1, 23., 5., 9, -5])
p0 = np.zeros(5)
c = constant(p, 1., 3.)
self.assertTrue(array_equal(c.derivate(1., 1), p0))
self.assertTrue(array_equal(c.derivate(1., 2), p0))
self.assertTrue(array_equal(c.derivate(3., 1), p0))
self.assertTrue(array_equal(c.derivate(1.5, 1), p0))
with self.assertRaises(ValueError):
c.derivate(0.5, 1)
with self.assertRaises(ValueError):
c.derivate(4., 3)
c_deriv = c.compute_derivate(1)
self.assertTrue(array_equal(c_deriv(1.5), p0))
self.assertEqual(c_deriv.min(), c.min())
self.assertEqual(c_deriv.max(), c.max())
self.assertEqual(c_deriv.dim(), c.dim())
def test_comparator(self):
p = array([1, 23., 5., 9, -5])
c1 = constant(p, 1., 3.)
c2 = constant(p, 1., 3.)
c3 = c1
pn = array([1, 23., 5., 9])
p2 = array([1, 17., 5., 9, -5])
cn1 = constant(pn, 1., 3.)
cn2 = constant(p, 1.5, 3.)
cn3 = constant(p, 1., 2.)
cn4 = constant(p2, 1., 3.)
self.assertEqual(c1, c2)
self.assertEqual(c1, c3)
self.assertNotEqual(c1, cn1)
self.assertNotEqual(c1, cn2)
self.assertNotEqual(c1, cn3)
self.assertNotEqual(c1, cn4)
self.assertTrue(c1.isEquivalent(c2))
def test_serialization(self):
p = array([1, 23., 5., 9, -5])
c = constant(p, 1., 3.)
c.saveAsText("serialization_curve.txt")
c.saveAsXML("serialization_curve.xml", "constant")
c.saveAsBinary("serialization_curve")
c_txt = constant()
c_txt.loadFromText("serialization_curve.txt")
self.assertEqual(c, c_txt)
c_xml = constant()
c_xml.loadFromXML("serialization_curve.xml", "constant")
self.assertEqual(c, c_xml)
c_bin = constant()
c_bin.loadFromBinary("serialization_curve")
self.assertEqual(c, c_bin)
class Constant3CurveTest(unittest.TestCase):
def test_constructor(self):
# default constructor
c = constant()
self.assertEqual(c.min(), 0.)
self.assertEqual(c.max(), 0)
self.assertEqual(c.dim(), 0)
self.assertEqual(c.degree(), 0)
# constructor from a point
p = array([1, 23., 5.])
c = constant3(p)
self.assertEqual(c.min(), 0.)
self.assertTrue(c.max() > 1e100) # convert std::numeric_limits<time_t>::max() to python ?
self.assertEqual(c.dim(), 3)
self.assertEqual(c.degree(), 0)
# constructor with timing
c = constant3(p, 1., 5.)
self.assertEqual(c.min(), 1.)
self.assertEqual(c.max(), 5.)
self.assertEqual(c.dim(), 3)
self.assertEqual(c.degree(), 0)
with self.assertRaises(ValueError):
c = constant(p, 2., 1.)