Cubic B-Spline trajectory. More...
#include <roboptim/trajectory/cubic-b-spline.hh>
  
 Public Types | |
| typedef Polynomial3 | polynomial_t | 
| Polynomial type.   | |
| typedef std::vector < polynomial_t, Eigen::aligned_allocator < polynomial_t > >  | basisPolynomials_t | 
| Basis polynomials type.   | |
| typedef std::vector < basisPolynomials_t >  | basisPolynomialsVector_t | 
| Basis polynomials vector type.   | |
| typedef basisPolynomials_t  polynomials3vector_t  | ROBOPTIM_TRAJECTORY_DEPRECATED | 
| Legacy typedef.   | |
| typedef  basisPolynomialsVector_t polynomials3vectors_t  | ROBOPTIM_TRAJECTORY_DEPRECATED | 
| Legacy typedef.   | |
| typedef vector_t | knots_t | 
| Knot vector type.   | |
Public Member Functions | |
| CubicBSpline (interval_t timeRange, size_type dimension, const vector_t ¶meters, const std::string name="cubic B-Spline", bool clamped=false) | |
| Instantiate a uniform cubic B-Spline from its definition.   | |
| CubicBSpline (size_type dimension, const knots_t &knots, const vector_t ¶meters, const std::string name="cubic B-Spline") | |
| Instantiate a cubic B-Spline from its definition.   | |
| CubicBSpline (const CubicBSpline &spline) | |
| Copy constructor.   | |
| virtual | ~CubicBSpline () | 
| virtual void | setParameters (const_vector_ref) | 
| Modify spline parameters.   | |
| 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.   | |
| virtual vector_t | derivBeforeSingularPoint (size_type rank, size_type order) const | 
| Get left limit value of derivative at given singular point.   | |
| virtual vector_t | derivAfterSingularPoint (size_type rank, size_type order) const | 
| Get right limit value of derivative at given singular point.   | |
| virtual Trajectory < derivabilityOrder > *  | resize (interval_t timeRange) const | 
| Clone and resize a trajectory.   | |
| virtual std::ostream & | print (std::ostream &o) const | 
| Display the function on the specified output stream.   | |
| jacobian_t | variationConfigWrtParam (StableTimePoint tp) const | 
| jacobian_t | variationDerivWrtParam (StableTimePoint tp, size_type order) const | 
| template<typename P > | |
| void | freezeCurveStart (P &problem, size_type offset=0) const | 
| Add a constraint to a problem in order to freeze the B-spline at its start.   | |
| template<typename P > | |
| void | freezeCurveEnd (P &problem, size_type offset=0) const | 
| Add a constraint to a problem in order to freeze the B-spline at its end.   | |
| value_type | Dt () const ROBOPTIM_TRAJECTORY_DEPRECATED | 
| Regular spacing between B-spline knots.   | |
| void | translateBasisPolynomials (value_type t1) | 
| Translate the basis polynomials to a given time t1.   | |
| void | toPolynomials (basisPolynomials_t &res) const | 
| Return the polynomial expression of the cubic B-spline on each time interval.   | |
| const basisPolynomialsVector_t & | basisPolynomials () const | 
| Constant getter for the basis polynomials of the cubic B-spline.   | |
| size_type | interval (value_type t) const | 
| Find the index of the interval in which t is.   | |
| size_type | getNumberControlPoints () const | 
| Get the number of control points of the spline.   | |
| const knots_t & | knotVector () const | 
| Return the knot vector of the spline.   | |
| CubicBSpline | operator+ (const CubicBSpline &s) const | 
| Add two cubic B-splines, supposing they have the same dimensions.   | |
| void | operator+= (const CubicBSpline &s) | 
| Add a second B-spline to this B-spline.   | |
| int | order () const | 
| Retrieve the order of the spline.   | |
Protected Member Functions | |
| 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 | 
| void | computeBasisPolynomials () | 
| Compute the basis polynomials for the cubic B-spline.   | |
| vector_t | basisFunctions (value_type t, size_type order) const ROBOPTIM_TRAJECTORY_DEPRECATED | 
| Compute the basis functions for a given instant t.   | |
Cubic B-Spline trajectory.
Implement a B-Spline as a trajectory as described in doc/cubic-b-spline.tex
| typedef std::vector< polynomial_t, Eigen::aligned_allocator<polynomial_t> > roboptim::trajectory::CubicBSpline::basisPolynomials_t | 
Basis polynomials type.
| typedef std::vector<basisPolynomials_t> roboptim::trajectory::CubicBSpline::basisPolynomialsVector_t | 
Basis polynomials vector type.
| typedef vector_t roboptim::trajectory::CubicBSpline::knots_t | 
Knot vector type.
| typedef basisPolynomials_t polynomials3vector_t roboptim::trajectory::CubicBSpline::ROBOPTIM_TRAJECTORY_DEPRECATED | 
Legacy typedef.
| typedef basisPolynomialsVector_t polynomials3vectors_t roboptim::trajectory::CubicBSpline::ROBOPTIM_TRAJECTORY_DEPRECATED | 
Legacy typedef.
| roboptim::trajectory::CubicBSpline::CubicBSpline | ( | interval_t | timeRange, | 
| size_type | dimension, | ||
| const vector_t & | parameters, | ||
| const std::string | name = "cubic B-Spline",  | 
        ||
| bool | clamped = false  | 
        ||
| ) | 
Instantiate a uniform cubic 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 | 
The number of control points is inferred from the dimension of the parameter vector.
References computeBasisPolynomials(), roboptim::trajectory::Trajectory< 3 >::parameters_, and setParameters().
Referenced by resize().
| roboptim::trajectory::CubicBSpline::CubicBSpline | ( | size_type | dimension, | 
| const knots_t & | knots, | ||
| const vector_t & | parameters, | ||
| const std::string | name = "cubic B-Spline"  | 
        ||
| ) | 
Instantiate a cubic B-Spline from its definition.
| dimension | spline dimension: \(n\) | 
| knots | vector of knots, | 
| parameters | vector of parameters defining control points | 
| name | function title | 
The number of control points is inferred from the dimension of the parameter vector.
References computeBasisPolynomials(), roboptim::trajectory::Trajectory< 3 >::parameters_, and setParameters().
| roboptim::trajectory::CubicBSpline::CubicBSpline | ( | const CubicBSpline & | spline | ) | 
Copy constructor.
| spline | spline that will be copied | 
References roboptim::trajectory::Trajectory< DerivabilityOrder >::parameters(), roboptim::trajectory::Trajectory< 3 >::parameters_, and setParameters().
| roboptim::trajectory::CubicBSpline::~CubicBSpline | ( | ) |  [virtual] | 
        
| CubicBSpline::vector_t roboptim::trajectory::CubicBSpline::basisFunctions | ( | value_type | t, | 
| size_type | order | ||
| ) |  const [protected] | 
        
Compute the basis functions for a given instant t.
| t | instant considered. | 
| order | order of the basis functions. | 
References Dt(), roboptim::trajectory::detail::fixTime(), interval(), roboptim::trajectory::Trajectory< 3 >::length(), roboptim::trajectory::Trajectory< 3 >::timeRange(), and roboptim::trajectory::Trajectory< 3 >::tolerance().
| const basisPolynomialsVector_t& roboptim::trajectory::CubicBSpline::basisPolynomials | ( | ) |  const [inline] | 
        
Constant getter for the basis polynomials of the cubic B-spline.
Note: computeBasisPolynomials() needs to be called beforehand (which is done in the CubicBSpline constructor).
| void roboptim::trajectory::CubicBSpline::computeBasisPolynomials | ( | ) |  [protected] | 
        
Compute the basis polynomials for the cubic B-spline.
Referenced by CubicBSpline().
| CubicBSpline::vector_t roboptim::trajectory::CubicBSpline::derivAfterSingularPoint | ( | size_type | rank, | 
| size_type | order | ||
| ) |  const [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< 3 >.
References roboptim::trajectory::Trajectory< 3 >::derivative(), and singularPointAtRank().
| CubicBSpline::vector_t roboptim::trajectory::CubicBSpline::derivBeforeSingularPoint | ( | size_type | rank, | 
| size_type | order | ||
| ) |  const [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< 3 >.
References roboptim::trajectory::Trajectory< 3 >::derivative(), and singularPointAtRank().
| CubicBSpline::value_type roboptim::trajectory::CubicBSpline::Dt | ( | ) | const | 
Regular spacing between B-spline knots.
This is only valid for uniform B-splines.
References roboptim::trajectory::Trajectory< 3 >::length().
Referenced by basisFunctions().
| void roboptim::trajectory::CubicBSpline::freezeCurveEnd | ( | P & | problem, | 
| size_type | offset = 0  | 
        ||
| ) | const | 
Add a constraint to a problem in order to freeze the B-spline at its end.
| problem | problem to which the constraint will be added. | 
| offset | offset of the B-spline parameters in the problem's parameter list. | 
References interval(), and roboptim::trajectory::Trajectory< 3 >::parameters().
| void roboptim::trajectory::CubicBSpline::freezeCurveStart | ( | P & | problem, | 
| size_type | offset = 0  | 
        ||
| ) | const | 
Add a constraint to a problem in order to freeze the B-spline at its start.
| problem | problem to which the constraint will be added. | 
| offset | offset of the B-spline parameters in the problem's parameter list. | 
References interval(), and roboptim::trajectory::Trajectory< 3 >::parameters().
| size_type roboptim::trajectory::CubicBSpline::getNumberControlPoints | ( | ) |  const [inline] | 
        
Get the number of control points of the spline.
Referenced by roboptim::trajectory::visualization::matplotlib::plot_spline().
| void roboptim::trajectory::CubicBSpline::impl_compute | ( | result_ref | , | 
| value_type | |||
| ) |  const [protected] | 
        
| void roboptim::trajectory::CubicBSpline::impl_derivative | ( | derivative_ref | g, | 
| value_type | x, | ||
| size_type | order | ||
| ) |  const [protected] | 
        
ROBOPTIM_DO_NOT_CHECK_ALLOCATION
ROBOPTIM_DO_NOT_CHECK_ALLOCATION
References roboptim::trajectory::Polynomial< N >::derivative(), roboptim::trajectory::detail::fixTime(), interval(), and roboptim::trajectory::Trajectory< 3 >::parameters().
Referenced by impl_derivative().
| void roboptim::trajectory::CubicBSpline::impl_derivative | ( | derivative_ref | g, | 
| StableTimePoint | stp, | ||
| size_type | order | ||
| ) |  const [protected, virtual] | 
        
Implements roboptim::trajectory::Trajectory< 3 >.
References roboptim::trajectory::StableTimePoint::getTime(), and impl_derivative().
| CubicBSpline::size_type roboptim::trajectory::CubicBSpline::interval | ( | value_type | t | ) | const | 
Find the index of the interval in which t is.
| t | instant considered. | 
References roboptim::trajectory::detail::fixTime(), and roboptim::trajectory::Trajectory< 3 >::timeRange().
Referenced by basisFunctions(), freezeCurveEnd(), freezeCurveStart(), and impl_derivative().
| const knots_t& roboptim::trajectory::CubicBSpline::knotVector | ( | ) |  const [inline] | 
        
Return the knot vector of the spline.
Referenced by roboptim::trajectory::visualization::matplotlib::plot_spline().
| CubicBSpline roboptim::trajectory::CubicBSpline::operator+ | ( | const CubicBSpline & | s | ) | const | 
Add two cubic B-splines, supposing they have the same dimensions.
| s | other B-spline with the same dimensions. | 
| std::runtime_error | if splines do not have the same dimensions. | 
References roboptim::trajectory::Trajectory< 3 >::parameters(), roboptim::trajectory::Trajectory< DerivabilityOrder >::parameters(), roboptim::trajectory::Trajectory< 3 >::timeRange(), and roboptim::trajectory::Trajectory< DerivabilityOrder >::timeRange().
| void roboptim::trajectory::CubicBSpline::operator+= | ( | const CubicBSpline & | s | ) | 
Add a second B-spline to this B-spline.
| s | other B-spline with the same dimensions. | 
| std::runtime_error | if splines do not have the same dimensions. | 
References roboptim::trajectory::Trajectory< 3 >::parameters(), roboptim::trajectory::Trajectory< DerivabilityOrder >::parameters(), setParameters(), roboptim::trajectory::Trajectory< 3 >::timeRange(), and roboptim::trajectory::Trajectory< DerivabilityOrder >::timeRange().
| int roboptim::trajectory::CubicBSpline::order | ( | ) | const | 
Retrieve the order of the spline.
| std::ostream & roboptim::trajectory::CubicBSpline::print | ( | std::ostream & | o | ) |  const [virtual] | 
        
Display the function on the specified output stream.
| o | output stream used for display | 
Reimplemented from roboptim::trajectory::Trajectory< 3 >.
References roboptim::trajectory::Trajectory< 3 >::length(), and roboptim::trajectory::Trajectory< 3 >::parameters().
| virtual Trajectory<derivabilityOrder>* roboptim::trajectory::CubicBSpline::resize | ( | interval_t | timeRange | ) |  const [inline, virtual] | 
        
Clone and resize a trajectory.
Implements roboptim::trajectory::Trajectory< 3 >.
References CubicBSpline(), and roboptim::trajectory::Trajectory< 3 >::parameters().
| void roboptim::trajectory::CubicBSpline::setParameters | ( | const_vector_ref | p | ) |  [virtual] | 
        
Modify spline parameters.
Reimplemented from roboptim::trajectory::Trajectory< 3 >.
References roboptim::trajectory::Trajectory< 3 >::parameters_.
Referenced by CubicBSpline(), roboptim::trajectory::SplineLength::impl_compute(), roboptim::trajectory::SplineLength::impl_gradient(), and operator+=().
| CubicBSpline::value_type roboptim::trajectory::CubicBSpline::singularPointAtRank | ( | size_type | rank | ) |  const [virtual] | 
        
Get singular point at given rank.
Implements roboptim::trajectory::Trajectory< 3 >.
References roboptim::trajectory::Trajectory< 3 >::length().
Referenced by derivAfterSingularPoint(), and derivBeforeSingularPoint().
| void roboptim::trajectory::CubicBSpline::toPolynomials | ( | basisPolynomials_t & | res | ) | const | 
Return the polynomial expression of the cubic B-spline on each time interval.
ROBOPTIM_DO_NOT_CHECK_ALLOCATION
ROBOPTIM_DO_NOT_CHECK_ALLOCATION
References roboptim::trajectory::Trajectory< 3 >::parameters().
Referenced by roboptim::trajectory::visualization::matplotlib::plot_spline().
| void roboptim::trajectory::CubicBSpline::translateBasisPolynomials | ( | value_type | t1 | ) | 
Translate the basis polynomials to a given time t1.
| t1 | new center time, i.e. P = sum(a_i*(t-t1)^i, i={0,3}) | 
This method can be useful when one needs to have all the polynomials expressed in the same basis (e.g. t1 = 0).
| virtual jacobian_t roboptim::trajectory::CubicBSpline::variationConfigWrtParam | ( | value_type | t | ) |  const [virtual] | 
        
Referenced by variationConfigWrtParam().
| CubicBSpline::jacobian_t roboptim::trajectory::CubicBSpline::variationConfigWrtParam | ( | StableTimePoint | tp | ) |  const [virtual] | 
        
Implements roboptim::trajectory::Trajectory< 3 >.
References roboptim::trajectory::StableTimePoint::getTime(), and variationConfigWrtParam().
| virtual jacobian_t roboptim::trajectory::CubicBSpline::variationDerivWrtParam | ( | value_type | t, | 
| size_type | order | ||
| ) |  const [virtual] | 
        
Referenced by variationDerivWrtParam().
| CubicBSpline::jacobian_t roboptim::trajectory::CubicBSpline::variationDerivWrtParam | ( | StableTimePoint | tp, | 
| size_type | order | ||
| ) |  const [virtual] | 
        
Implements roboptim::trajectory::Trajectory< 3 >.
References roboptim::trajectory::StableTimePoint::getTime(), and variationDerivWrtParam().