#include <roboptim/trajectory/b-spline.hh>
Public Types | |
typedef parent_t::interval_t | interval_t |
typedef Polynomial< N > | polynomial_t |
typedef Monomial< N > | monomial_t |
typedef std::map< int, polynomial_t, std::less< int > , Eigen::aligned_allocator < std::pair< const int, polynomial_t > > > | cox_map |
typedef cox_map::iterator | cox_map_itr_t |
typedef std::vector < polynomial_t, Eigen::aligned_allocator < polynomial_t > > | basisPolynomials_t |
typedef std::vector < basisPolynomials_t > | basisPolynomialsVector_t |
Public Types inherited from roboptim::trajectory::Trajectory< N > | |
typedef parent_t::interval_t | interval_t |
Import interval type. More... | |
Public Member Functions | |
ROBOPTIM_NTIMES_DERIVABLE_FUNCTION_FWD_TYPEDEFS_ (Trajectory< N >) | |
Parent type and imports. More... | |
BSpline (const interval_t &timeRange, size_type dimension, const vector_t ¶meters, const std::string name="B-Spline", bool clamped=false) | |
Instantiate a B-Spline from its definition. More... | |
BSpline (const interval_t &tr, size_type dimension, const vector_t ¶meters, const_vector_ref knots, std::string name="B-Spline") | |
Instantiate a B-Spline with parameters and knot points. More... | |
BSpline (const BSpline< N > &spline) | |
Copy constructor. More... | |
template<int M> | |
BSpline< N > | derivative () const |
Compute the derivative of the B-spline for a given order. More... | |
virtual | ~BSpline () |
Virtual destructor. More... | |
virtual void | setParameters (const_vector_ref) |
Modify spline parameters. More... | |
virtual jacobian_t | variationConfigWrtParam (value_type t) const |
virtual jacobian_t | variationDerivWrtParam (value_type t, size_type order) const |
virtual value_type | singularPointAtRank (size_type rank) const |
Get singular point at given rank. More... | |
virtual vector_t | derivBeforeSingularPoint (size_type rank, size_type order) const |
Get left limit value of derivative at given singular point. More... | |
virtual vector_t | derivAfterSingularPoint (size_type rank, size_type order) const |
Get right limit value of derivative at given singular point. More... | |
virtual Trajectory< N > * | resize (interval_t timeRange) const |
Clone and resize a trajectory. More... | |
virtual std::ostream & | print (std::ostream &o) const |
Display the function on the specified output stream. More... | |
jacobian_t | variationConfigWrtParam (StableTimePoint tp) const |
jacobian_t | variationDerivWrtParam (StableTimePoint tp, size_type order) const |
value_type | Dt () const ROBOPTIM_TRAJECTORY_DEPRECATED |
const vector_t & | knotVector () const |
Return the knot vector of the spline. More... | |
size_type | interval (value_type t) const |
size_type | getNumberControlPoints () const |
Get the number of control points of the spline. More... | |
void | toPolynomials (basisPolynomials_t &res) const |
Return the polynomial expression of the B-spline on each time interval. More... | |
const basisPolynomialsVector_t & | basisPolynomials () const |
Constant getter for the basis polynomials of the B-spline. More... | |
int | order () const |
Retrieve the order of the spline. More... | |
template<int M> | |
BSpline< N > ::basisPolynomialsVector_t | deriveBasisPolynomials () const |
Public Member Functions inherited from roboptim::trajectory::Trajectory< N > | |
ROBOPTIM_NTIMES_DERIVABLE_FUNCTION_FWD_TYPEDEFS_ (NTimesDerivableFunction< DerivabilityOrder >) | |
Parent type and imports. More... | |
virtual | ~Trajectory () |
result_t | operator() (StableTimePoint argument) const |
void | operator() (result_ref result, StableTimePoint argument) const |
derivative_t | derivative (StableTimePoint argument, size_type order=1) const |
void | derivative (derivative_ref derivative, StableTimePoint argument, size_type order=1) const |
bool | isValidTime (value_type t) const |
virtual void | normalizeAngles (size_type index) |
Normalize angles in parameters array. More... | |
virtual Trajectory < DerivabilityOrder > * | clone () const =0 |
const vector_t & | parameters () const |
interval_t | timeRange () const |
value_type | length () const |
virtual vector_t | state (double t, size_type order) const |
Get state along trajectory. More... | |
virtual vector_t | state (StableTimePoint t, size_type order) const |
virtual jacobian_t | variationConfigWrtParam (double t) const =0 |
Get the variation of a configuration with respect to parameter vector. More... | |
virtual jacobian_t | variationDerivWrtParam (double t, size_type order) const =0 |
Get the variation of a derivative with respect to parameter vector. More... | |
jacobian_t | variationStateWrtParam (double t, size_type order) const |
Get the variation of the state with respect to parameter vector. More... | |
jacobian_t | variationStateWrtParam (StableTimePoint stp, size_type order) const |
size_type | singularPoints () const |
Get number of singular points. More... | |
void | tolerance (const double &tolerance) |
double | tolerance () const |
Get tolerance for inclusion of parameter in interval of definition. More... | |
Protected Types | |
enum | ConstructionMode { NORMAL = 0, UNINITIALIZED = 1 } |
Enum for special constructors. More... | |
Protected Member Functions | |
BSpline (ConstructionMode mode, const interval_t &timeRange, size_type dimension, const vector_t ¶meters, const std::string name="B-Spline", bool clamped=false) | |
Special constructor used internally for specific cases (e.g. More... | |
void | impl_compute (result_ref, value_type) const |
void | impl_derivative (derivative_ref g, value_type x, size_type order) const |
void | impl_derivative (derivative_ref g, StableTimePoint, size_type order) const |
vector_t | basisFunctions (value_type t, size_type order) const ROBOPTIM_TRAJECTORY_DEPRECATED |
void | computeBasisPolynomials () |
Compute the basis polynomials. More... | |
template<int M> | |
basisPolynomialsVector_t | deriveBasisPolynomials () const |
Derive basis polynomials, but express the result as polynomials of BSpline<N> instead of BSpline<N-M>. More... | |
cox_map | cox_de_boor (size_type j, size_type n) const |
Generate base polynomial set For the basic spline formula noted in the pdf from the docs section, this implements (3), the recursion formula. More... | |
void | initializeKnots (bool clamped) |
Initialize the knot vector. More... | |
Protected Member Functions inherited from roboptim::trajectory::Trajectory< N > | |
virtual void | normalizeAngles (size_type index, size_type offset) |
Internal version of normalizeAngles allowing an optional offset. More... | |
void | impl_compute (result_ref, StableTimePoint) const |
Trajectory (interval_t, size_type, const vector_t &, std::string name=std::string()) | |
Static Protected Attributes | |
static const size_type | order_ = N |
Order of the B-Spline. More... | |
static log4cxx::LoggerPtr | logger |
Pointer to B-spline logger (see log4cxx documentation). More... | |
Additional Inherited Members | |
Protected Attributes inherited from roboptim::trajectory::Trajectory< N > | |
interval_t | timeRange_ |
vector_t | parameters_ |
size_type | singularPoints_ |
typedef std::vector< polynomial_t, Eigen::aligned_allocator<polynomial_t> > roboptim::trajectory::BSpline< N >::basisPolynomials_t |
typedef std::vector<basisPolynomials_t> roboptim::trajectory::BSpline< N >::basisPolynomialsVector_t |
typedef std::map< int, polynomial_t, std::less<int>, Eigen::aligned_allocator<std::pair<const int, polynomial_t> > > roboptim::trajectory::BSpline< N >::cox_map |
typedef cox_map::iterator roboptim::trajectory::BSpline< N >::cox_map_itr_t |
typedef parent_t::interval_t roboptim::trajectory::BSpline< N >::interval_t |
typedef Monomial<N> roboptim::trajectory::BSpline< N >::monomial_t |
typedef Polynomial<N> roboptim::trajectory::BSpline< N >::polynomial_t |
|
protected |
roboptim::trajectory::BSpline< N >::BSpline | ( | const interval_t & | timeRange, |
size_type | dimension, | ||
const vector_t & | parameters, | ||
const std::string | name = "B-Spline" , |
||
bool | clamped = false |
||
) |
Instantiate a B-Spline from its definition.
timeRange | spline time range: $ \([t_3,t_n]\) |
dimension | spline dimension: \(n\) |
parameters | vector of parameters defining control points |
name | function title |
clamped | whether the spline should be clamped |
Number of control points is inferred from dimension of parameter vector.
References roboptim::trajectory::BSpline< N >::computeBasisPolynomials(), roboptim::trajectory::BSpline< N >::initializeKnots(), roboptim::trajectory::BSpline< N >::order_, roboptim::trajectory::Trajectory< N >::parameters_, and roboptim::trajectory::BSpline< N >::setParameters().
roboptim::trajectory::BSpline< N >::BSpline | ( | const interval_t & | tr, |
size_type | dimension, | ||
const vector_t & | parameters, | ||
const_vector_ref | knots, | ||
std::string | name = "B-Spline" |
||
) |
Instantiate a B-Spline with parameters and knot points.
timeRange | spline time range: $ \([t_3,t_n]\) |
dimension | spline dimension: \(n\) |
parameters | vector of parameters |
knots | vector of control points |
name | function title The number of knot points must be the number of parameters + N + 1. In the knot vector, N knots at the beginning must lie before the start of the spline. The rest of the knot point must lie before the end of the spline interval. |
References roboptim::trajectory::BSpline< N >::computeBasisPolynomials(), roboptim::trajectory::BSpline< N >::order_, roboptim::trajectory::Trajectory< N >::parameters_, and roboptim::trajectory::BSpline< N >::setParameters().
roboptim::trajectory::BSpline< N >::BSpline | ( | const BSpline< N > & | spline | ) |
Copy constructor.
spline | spline that will be copied. |
References roboptim::trajectory::BSpline< N >::order_, roboptim::trajectory::Trajectory< N >::parameters(), roboptim::trajectory::Trajectory< N >::parameters_, and roboptim::trajectory::BSpline< N >::setParameters().
|
inlinevirtual |
Virtual destructor.
|
protected |
Special constructor used internally for specific cases (e.g.
spline derivation).
timeRange | time range of the spline. |
dimension | output dimension. |
parameters | control point vector. |
name | name of the spline. |
clamped | whether the spline is clamped. |
References roboptim::trajectory::BSpline< N >::computeBasisPolynomials(), roboptim::trajectory::BSpline< N >::initializeKnots(), roboptim::trajectory::BSpline< N >::NORMAL, roboptim::trajectory::BSpline< N >::order_, roboptim::trajectory::Trajectory< N >::parameters_, and roboptim::trajectory::BSpline< N >::setParameters().
|
protected |
|
inline |
Constant getter for the basis polynomials of the B-spline.
Note: computeBasisPolynomials() needs to be called beforehand (which is done in the BSpline constructor).
|
protected |
Compute the basis polynomials.
Referenced by roboptim::trajectory::BSpline< N >::BSpline().
|
protected |
Generate base polynomial set For the basic spline formula noted in the pdf from the docs section, this implements (3), the recursion formula.
It returns the results as factors of b_j,0 where j is the index of the returned map.
j | current knot index |
n | current basis function order |
|
virtual |
Get right limit value of derivative at given singular point.
rank | rank of the singular points. |
order | order of derivation. |
derivative | Limit of the derivative at singular point for decreasing parameter values. |
Implements roboptim::trajectory::Trajectory< N >.
BSpline< N > roboptim::trajectory::BSpline< N >::derivative | ( | ) | const |
Compute the derivative of the B-spline for a given order.
Note: here we return a spline of the same degree for simplicity (we keep the same knot vector), but the basis polynomials are M degrees lower.
M | derivation order (M ≥ 0). |
|
virtual |
Get left limit value of derivative at given singular point.
rank | rank of the singular points. |
order | order of derivation. |
Implements roboptim::trajectory::Trajectory< N >.
BSpline<N>::basisPolynomialsVector_t roboptim::trajectory::BSpline< N >::deriveBasisPolynomials | ( | ) | const |
|
protected |
Derive basis polynomials, but express the result as polynomials of BSpline<N> instead of BSpline<N-M>.
M | derivation order. |
BSpline< N >::value_type roboptim::trajectory::BSpline< N >::Dt | ( | ) | const |
|
inline |
Get the number of control points of the spline.
Referenced by roboptim::trajectory::visualization::matplotlib::plot_spline().
|
protected |
References roboptim::trajectory::detail::fixTime().
|
protected |
|
protectedvirtual |
Implements roboptim::trajectory::Trajectory< N >.
References roboptim::trajectory::StableTimePoint::getTime().
|
protected |
Initialize the knot vector.
clamped | whether the spline is clamped. |
Referenced by roboptim::trajectory::BSpline< N >::BSpline().
BSpline< N >::size_type roboptim::trajectory::BSpline< N >::interval | ( | value_type | t | ) | const |
References roboptim::trajectory::detail::fixTime().
const BSpline< N >::vector_t & roboptim::trajectory::BSpline< N >::knotVector | ( | ) | const |
Return the knot vector of the spline.
Referenced by roboptim::trajectory::visualization::matplotlib::plot_spline().
int roboptim::trajectory::BSpline< N >::order | ( | ) | const |
Retrieve the order of the spline.
|
virtual |
Display the function on the specified output stream.
o | output stream used for display |
Reimplemented from roboptim::trajectory::Trajectory< N >.
|
virtual |
Clone and resize a trajectory.
Implements roboptim::trajectory::Trajectory< N >.
Reimplemented in roboptim::trajectory::ConstrainedBSpline< N >.
roboptim::trajectory::BSpline< N >::ROBOPTIM_NTIMES_DERIVABLE_FUNCTION_FWD_TYPEDEFS_ | ( | Trajectory< N > | ) |
Parent type and imports.
|
virtual |
Modify spline parameters.
Reimplemented from roboptim::trajectory::Trajectory< N >.
Reimplemented in roboptim::trajectory::ConstrainedBSpline< N >.
Referenced by roboptim::trajectory::BSpline< N >::BSpline().
|
virtual |
Get singular point at given rank.
Implements roboptim::trajectory::Trajectory< N >.
void roboptim::trajectory::BSpline< N >::toPolynomials | ( | basisPolynomials_t & | res | ) | const |
Return the polynomial expression of the B-spline on each time interval.
ROBOPTIM_DO_NOT_CHECK_ALLOCATION
ROBOPTIM_DO_NOT_CHECK_ALLOCATION
Referenced by roboptim::trajectory::visualization::matplotlib::plot_spline().
|
virtual |
|
virtual |
Implements roboptim::trajectory::Trajectory< N >.
References roboptim::trajectory::StableTimePoint::getTime().
|
virtual |
|
virtual |
Implements roboptim::trajectory::Trajectory< N >.
References roboptim::trajectory::StableTimePoint::getTime().
|
staticprotected |
Order of the B-Spline.
Referenced by roboptim::trajectory::BSpline< N >::BSpline().