#include <roboptim/trajectory/b-spline.hh>
  
 Public Types | |
| typedef parent_t::interval_t | interval_t | 
| Import interval type.   | |
| 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 Member Functions | |
| ROBOPTIM_NTIMES_DERIVABLE_FUNCTION_FWD_TYPEDEFS_ (Trajectory< N >) | |
| Parent type and imports.   | |
| 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.   | |
| 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.   | |
| BSpline (const BSpline< N > &spline) | |
| Copy constructor.   | |
| template<int M> | |
| BSpline< N > | derivative () const | 
| Compute the derivative of the B-spline for a given order.   | |
| virtual | ~BSpline () | 
| Virtual destructor.   | |
| 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< N > * | 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 | 
| value_type | Dt () const ROBOPTIM_TRAJECTORY_DEPRECATED | 
| const vector_t & | knotVector () const | 
| Return the knot vector of the spline.   | |
| size_type | interval (value_type t) const | 
| size_type | getNumberControlPoints () const | 
| Get the number of control points of the spline.   | |
| void | toPolynomials (basisPolynomials_t &res) const | 
| Return the polynomial expression of the B-spline on each time interval.   | |
| const basisPolynomialsVector_t & | basisPolynomials () const | 
| Constant getter for the basis polynomials of the B-spline.   | |
| int | order () const | 
| Retrieve the order of the spline.   | |
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.   | |
| 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.   | |
| template<int M> | |
| basisPolynomialsVector_t | deriveBasisPolynomials () const | 
| Derive basis polynomials, but express the result as polynomials of BSpline<N> instead of BSpline<N-M>.   | |
| 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.   | |
| void | initializeKnots (bool clamped) | 
| Initialize the knot vector.   | |
Static Protected Attributes | |
| static const size_type | order_ = N | 
| Order of the B-Spline.   | |
| static log4cxx::LoggerPtr | logger | 
| Pointer to B-spline logger (see log4cxx documentation).   | |
| 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 | 
Import interval type.
Reimplemented from roboptim::trajectory::Trajectory< N >.
Reimplemented in roboptim::trajectory::ConstrainedBSpline< N >.
| typedef Monomial<N> roboptim::trajectory::BSpline< N >::monomial_t | 
| typedef Polynomial<N> roboptim::trajectory::BSpline< N >::polynomial_t | 
enum roboptim::trajectory::BSpline::ConstructionMode [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().
| virtual roboptim::trajectory::BSpline< N >::~BSpline | ( | ) |  [inline, virtual] | 
        
Virtual destructor.
| roboptim::trajectory::BSpline< N >::BSpline | ( | ConstructionMode | mode, | 
| const interval_t & | timeRange, | ||
| size_type | dimension, | ||
| const vector_t & | parameters, | ||
| const std::string | name = "B-Spline",  | 
        ||
| bool | clamped = false  | 
        ||
| ) |  [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().
| BSpline< N >::vector_t roboptim::trajectory::BSpline< N >::basisFunctions | ( | value_type | t, | 
| size_type | order | ||
| ) |  const [protected] | 
        
| const basisPolynomialsVector_t& roboptim::trajectory::BSpline< N >::basisPolynomials | ( | ) |  const [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).
| void roboptim::trajectory::BSpline< N >::computeBasisPolynomials | ( | ) |  [protected] | 
        
Compute the basis polynomials.
Referenced by roboptim::trajectory::BSpline< N >::BSpline().
| BSpline< N >::cox_map roboptim::trajectory::BSpline< N >::cox_de_boor | ( | size_type | j, | 
| size_type | n | ||
| ) |  const [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 | 
References roboptim::trajectory::Polynomial< N >::coefs().
| BSpline< N >::vector_t roboptim::trajectory::BSpline< N >::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< 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). | 
| BSpline< N >::vector_t roboptim::trajectory::BSpline< N >::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< 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 | 
| size_type roboptim::trajectory::BSpline< N >::getNumberControlPoints | ( | ) |  const [inline] | 
        
Get the number of control points of the spline.
Referenced by roboptim::trajectory::visualization::matplotlib::plot_spline().
| void roboptim::trajectory::BSpline< N >::impl_compute | ( | result_ref | derivative, | 
| value_type | t | ||
| ) |  const [protected] | 
        
References roboptim::trajectory::detail::fixTime().
| void roboptim::trajectory::BSpline< N >::impl_derivative | ( | derivative_ref | g, | 
| value_type | x, | ||
| size_type | order | ||
| ) |  const [protected] | 
        
| void roboptim::trajectory::BSpline< N >::impl_derivative | ( | derivative_ref | g, | 
| StableTimePoint | stp, | ||
| size_type | order | ||
| ) |  const [protected, virtual] | 
        
Implements roboptim::trajectory::Trajectory< N >.
References roboptim::trajectory::StableTimePoint::getTime().
| void roboptim::trajectory::BSpline< N >::initializeKnots | ( | bool | clamped | ) |  [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.
| std::ostream & roboptim::trajectory::BSpline< N >::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< N >.
| Trajectory< N > * roboptim::trajectory::BSpline< N >::resize | ( | interval_t | timeRange | ) |  const [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.
| void roboptim::trajectory::BSpline< N >::setParameters | ( | const_vector_ref | p | ) |  [virtual] | 
        
Modify spline parameters.
Reimplemented from roboptim::trajectory::Trajectory< N >.
Reimplemented in roboptim::trajectory::ConstrainedBSpline< N >.
Referenced by roboptim::trajectory::BSpline< N >::BSpline().
| BSpline< N >::value_type roboptim::trajectory::BSpline< N >::singularPointAtRank | ( | size_type | rank | ) |  const [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().
| BSpline< N >::jacobian_t roboptim::trajectory::BSpline< N >::variationConfigWrtParam | ( | value_type | t | ) |  const [virtual] | 
        
| BSpline< N >::jacobian_t roboptim::trajectory::BSpline< N >::variationConfigWrtParam | ( | StableTimePoint | tp | ) |  const [virtual] | 
        
Implements roboptim::trajectory::Trajectory< N >.
References roboptim::trajectory::StableTimePoint::getTime().
| BSpline< N >::jacobian_t roboptim::trajectory::BSpline< N >::variationDerivWrtParam | ( | value_type | t, | 
| size_type | order | ||
| ) |  const [virtual] | 
        
| BSpline< N >::jacobian_t roboptim::trajectory::BSpline< N >::variationDerivWrtParam | ( | StableTimePoint | tp, | 
| size_type | order | ||
| ) |  const [virtual] | 
        
Implements roboptim::trajectory::Trajectory< N >.
References roboptim::trajectory::StableTimePoint::getTime().
const size_type roboptim::trajectory::BSpline< N >::order_ = N [static, protected] | 
        
Order of the B-Spline.
Referenced by roboptim::trajectory::BSpline< N >::BSpline().