#include <BipedalLocomotion/Math/Spline.h>
template<typename T>
Spline class
Spline implement a basic spline.
Template parameters | |
---|---|
T | type of the spline. T must be an Eigen type (i.e. Eigen::Vector3d). |
Base classes
-
template<class Output>class BipedalLocomotion::System::Source<TrajectoryPoint<T>>
- Source is a template specialization of Advanceable and represents a block that does not contains input.
Derived classes
-
template<typename T>class CubicSpline
- Cubic spline implements a 3-rd order polynomial spline in .
-
template<typename T>class LinearSpline
- LinearSpline implements a 1-st order polynomial spline in .
-
template<typename T>class QuinticSpline
- Quintic spline implements a 5-th order polynomial spline in .
-
template<typename T>class ZeroOrderSpline
- ZeroOrderSpline implements a 0 order polynomial spline in .
Public types
- struct DerivativeBoundaryConditions
- BoundaryConditions is a struct that contains the boundary conditions of the spline.
Constructors, destructors, conversion operators
- ~Spline() defaulted virtual
- Destructor.
Public functions
- auto setAdvanceTimeStep(const std::chrono::nanoseconds& dt) -> bool
- Set the time step of the advance interface.
- auto setKnots(const std::vector<T>& position, const std::vector<std::chrono::nanoseconds>& time) -> bool
- Set the knots of the spline.
- auto setInitialConditions(const DerivativeBoundaryConditions& initialConditions) -> bool
- Set the initial condition of the spline.
- auto setFinalConditions(const DerivativeBoundaryConditions& finalConditions) -> bool
- Set the final condition of the spline.
- auto setInitialConditions(Eigen::Ref<const T> initialVelocity, Eigen::Ref<const T> initialAcceleration) -> bool
- Set the initial condition of the spline.
- auto setFinalConditions(Eigen::Ref<const T> finalVelocity, Eigen::Ref<const T> finalAcceleration) -> bool
- Set the final condition of the spline.
- auto evaluatePoint(const std::chrono::nanoseconds& t, Eigen::Ref<T> position, Eigen::Ref<T> velocity, Eigen::Ref<T> acceleration) -> bool
- Evaluate the spline at a given point.
- auto evaluatePoint(const std::chrono::nanoseconds& t, Eigen::Ref<T> position) -> bool
- Evaluate the spline at a given point.
- auto evaluatePoint(const std::chrono::nanoseconds& t, Eigen::Ref<T> position, Eigen::Ref<T> velocity) -> bool
- Evaluate the spline at a given point.
- auto evaluateOrderedPoints(const std::vector<std::chrono::nanoseconds>& t, std::vector<T>& position, std::vector<T>& velocity, std::vector<T>& acceleration) -> bool
- Evaluate the spline at given set of points.
- auto evaluatePoint(const std::chrono::nanoseconds& t, TrajectoryPoint<T>& state) -> bool
- Evaluate the spline at a given point.
- auto isOutputValid() const -> bool final
- Check if the output is valid.
- auto getOutput() const -> const TrajectoryPoint<T>& final
- Get the output of the system.
- auto advance() -> bool final
- Advance the system.
Protected types
- struct Polynomial
- Polynomial is a struct that contains the information of a polynomial.
Protected functions
- auto computePhasesDuration() -> bool
- Compute the duration of each phase (sub-trajectory).
- void computeIntermediateQuantities() pure virtual
- Compute the intermediate quantities of the spline.
- void updatePolynomialCoefficients(Polynomial& polynomial) pure virtual
- Set the coefficients of the polynomial.
Protected variables
- std::vector<TrajectoryPoint<T>> m_knots
- Knots of the spline.
- std::vector<Polynomial> m_polynomials
- Polynomials of the spline.
Function documentation
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: setAdvanceTimeStep(const std::chrono::nanoseconds& dt)
Set the time step of the advance interface.
Parameters | |
---|---|
dt | the time step of the advance block. |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: setKnots(const std::vector<T>& position,
const std::vector<std::chrono::nanoseconds>& time)
Set the knots of the spline.
Parameters | |
---|---|
position | position of the knots in . |
time | vector containing the time instant of the knots. |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: setInitialConditions(const DerivativeBoundaryConditions& initialConditions)
Set the initial condition of the spline.
Parameters | |
---|---|
initialConditions | initial conditions of the spline. |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: setFinalConditions(const DerivativeBoundaryConditions& finalConditions)
Set the final condition of the spline.
Parameters | |
---|---|
finalConditions | final conditions of the spline. |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: setInitialConditions(Eigen::Ref<const T> initialVelocity,
Eigen::Ref<const T> initialAcceleration)
Set the initial condition of the spline.
Returns | True in case of success, false otherwise. |
---|
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: setFinalConditions(Eigen::Ref<const T> finalVelocity,
Eigen::Ref<const T> finalAcceleration)
Set the final condition of the spline.
Returns | True in case of success, false otherwise. |
---|
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: evaluatePoint(const std::chrono::nanoseconds& t,
Eigen::Ref<T> position,
Eigen::Ref<T> velocity,
Eigen::Ref<T> acceleration)
Evaluate the spline at a given point.
Parameters | |
---|---|
t | instant time |
position | position at time t |
velocity | velocity at time t |
acceleration | acceleration at time t |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: evaluatePoint(const std::chrono::nanoseconds& t,
Eigen::Ref<T> position)
Evaluate the spline at a given point.
Parameters | |
---|---|
t | instant time |
position | position at time t |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: evaluatePoint(const std::chrono::nanoseconds& t,
Eigen::Ref<T> position,
Eigen::Ref<T> velocity)
Evaluate the spline at a given point.
Parameters | |
---|---|
t | instant time |
position | position at time t |
velocity | velocity at time t |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: evaluateOrderedPoints(const std::vector<std::chrono::nanoseconds>& t,
std::vector<T>& position,
std::vector<T>& velocity,
std::vector<T>& acceleration)
Evaluate the spline at given set of points.
Parameters | |
---|---|
t | ordered vector containing the time instant |
position | position at time t |
velocity | velocity at time t |
acceleration | acceleration at time t |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: evaluatePoint(const std::chrono::nanoseconds& t,
TrajectoryPoint<T>& state)
Evaluate the spline at a given point.
Parameters | |
---|---|
t | instant time |
state | of the system |
Returns | True in case of success, false otherwise. |
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: isOutputValid() const final
Check if the output is valid.
Returns | True if the output is valid, false otherwise. |
---|
template<typename T>
const TrajectoryPoint<T>& BipedalLocomotion:: Math:: Spline<T>:: getOutput() const final
Get the output of the system.
Returns | The output of the system. |
---|
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: advance() final
Advance the system.
Returns | True in case of success, false otherwise. |
---|
template<typename T>
bool BipedalLocomotion:: Math:: Spline<T>:: computePhasesDuration() protected
Compute the duration of each phase (sub-trajectory).
Returns | True in case of success, false otherwise. |
---|
template<typename T>
void BipedalLocomotion:: Math:: Spline<T>:: computeIntermediateQuantities() pure virtual protected
Compute the intermediate quantities of the spline.
Returns | True in case of success, false otherwise. |
---|
template<typename T>
void BipedalLocomotion:: Math:: Spline<T>:: updatePolynomialCoefficients(Polynomial& polynomial) pure virtual protected
Set the coefficients of the polynomial.
Parameters | |
---|---|
polynomial | polynomial to be updated. |
Returns | True in case of success, false otherwise. |