class
Splinespline implement an interface for a Spline in
Base classes
-
template<class Output>class BipedalLocomotion::System::Source<SplineState>
- Source is a template specialization of Advanceable and represents a block that does not contains input.
Derived classes
- class CubicSpline
- Cubic spline implement a 3-rd order polynomial spline in $f\mathbb{R}^n$f.
- class QuinticSpline
- Quintic spline implement a 5-th order polynomial spline in $f\mathbb{R}^n$f.
Constructors, destructors, conversion operators
- ~Spline() defaulted virtual
- Destructor.
Public functions
- auto setAdvanceTimeStep(const std::chrono::nanoseconds& dt) -> bool pure virtual
- Set the time step of the advance interface.
- auto setKnots(const std::vector<Eigen::VectorXd>& position, const std::vector<std::chrono::nanoseconds>& time) -> bool pure virtual
- Set the knots of the spline.
- auto setInitialConditions(Eigen::Ref<const Eigen::VectorXd> velocity, Eigen::Ref<const Eigen::VectorXd> acceleration) -> bool pure virtual
- Set the initial condition of the spline.
- auto setFinalConditions(Eigen::Ref<const Eigen::VectorXd> velocity, Eigen::Ref<const Eigen::VectorXd> acceleration) -> bool pure virtual
- Set the final condition of the spline.
- auto evaluatePoint(const std::chrono::nanoseconds& t, Eigen::Ref<Eigen::VectorXd> position, Eigen::Ref<Eigen::VectorXd> velocity, Eigen::Ref<Eigen::VectorXd> acceleration) -> bool pure virtual
- Evaluate the spline at a given point.
- auto evaluatePoint(const std::chrono::nanoseconds& t, SplineState& state) -> bool pure virtual
- Evaluate the spline at a given point.
Function documentation
bool BipedalLocomotion:: Planners:: Spline:: setAdvanceTimeStep(const std::chrono::nanoseconds& dt) pure virtual
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. |
bool BipedalLocomotion:: Planners:: Spline:: setKnots(const std::vector<Eigen::VectorXd>& position,
const std::vector<std::chrono::nanoseconds>& time) pure virtual
Set the knots of the spline.
Parameters | |
---|---|
position | position of the knots in $f\mathbb{R}^n$f. |
time | vector containing the time instant of the knots. |
Returns | True in case of success, false otherwise. |
bool BipedalLocomotion:: Planners:: Spline:: setInitialConditions(Eigen::Ref<const Eigen::VectorXd> velocity,
Eigen::Ref<const Eigen::VectorXd> acceleration) pure virtual
Set the initial condition of the spline.
Parameters | |
---|---|
velocity | initial velocity (i.e. first derivative). |
acceleration | initial acceleration (i.e. second derivative). |
Returns | True in case of success, false otherwise. |
bool BipedalLocomotion:: Planners:: Spline:: setFinalConditions(Eigen::Ref<const Eigen::VectorXd> velocity,
Eigen::Ref<const Eigen::VectorXd> acceleration) pure virtual
Set the final condition of the spline.
Parameters | |
---|---|
velocity | final velocity (i.e. first derivative). |
acceleration | final acceleration (i.e. second derivative). |
Returns | True in case of success, false otherwise. |
bool BipedalLocomotion:: Planners:: Spline:: evaluatePoint(const std::chrono::nanoseconds& t,
Eigen::Ref<Eigen::VectorXd> position,
Eigen::Ref<Eigen::VectorXd> velocity,
Eigen::Ref<Eigen::VectorXd> acceleration) pure virtual
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. |
bool BipedalLocomotion:: Planners:: Spline:: evaluatePoint(const std::chrono::nanoseconds& t,
SplineState& state) pure virtual
Evaluate the spline at a given point.
Parameters | |
---|---|
t | instant time |
state | of the system |
Returns | True in case of success, false otherwise. |