class
CubicSplineCubic spline implement a 3-rd order polynomial spline in $f\mathbb{R}^n$f.
Base classes
Constructors, destructors, conversion operators
- CubicSpline()
- Constructor.
- ~CubicSpline()
- Destructor.
Public functions
- auto setAdvanceTimeStep(const std::chrono::nanoseconds& dt) -> bool final
- Set the time step of the advance interface.
- auto setKnots(const std::vector<Eigen::VectorXd>& position, const std::vector<std::chrono::nanoseconds>& time) -> bool final
- Set the knots of the spline.
- auto setInitialConditions(Eigen::Ref<const Eigen::VectorXd> velocity, Eigen::Ref<const Eigen::VectorXd> acceleration) -> bool final
- Set the initial condition of the spline.
- auto setFinalConditions(Eigen::Ref<const Eigen::VectorXd> velocity, Eigen::Ref<const Eigen::VectorXd> acceleration) -> bool final
- Set the final condition of the spline.
- auto setInitialConditions(Eigen::Ref<const Eigen::VectorXd> velocity) -> bool
- Set the initial condition of the spline.
- auto setFinalConditions(Eigen::Ref<const Eigen::VectorXd> velocity) -> bool
- 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 final
- Evaluate the spline at a given point.
- auto evaluatePoint(const std::chrono::nanoseconds& t, SplineState& state) -> bool final
- Evaluate the spline at a given point.
- auto getOutput() const -> const SplineState& final
- Get the state of the system.
- auto isOutputValid() const -> bool final
- Determines the validity of the object retrieved with get()
- auto advance() -> bool final
- Advance the internal state.
Function documentation
BipedalLocomotion:: Planners:: CubicSpline:: ~CubicSpline()
Destructor.
bool BipedalLocomotion:: Planners:: CubicSpline:: setAdvanceTimeStep(const std::chrono::nanoseconds& dt) final
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:: CubicSpline:: setKnots(const std::vector<Eigen::VectorXd>& position,
const std::vector<std::chrono::nanoseconds>& time) final
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:: CubicSpline:: setInitialConditions(Eigen::Ref<const Eigen::VectorXd> velocity,
Eigen::Ref<const Eigen::VectorXd> acceleration) final
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:: CubicSpline:: setFinalConditions(Eigen::Ref<const Eigen::VectorXd> velocity,
Eigen::Ref<const Eigen::VectorXd> acceleration) final
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:: CubicSpline:: setInitialConditions(Eigen::Ref<const Eigen::VectorXd> velocity)
Set the initial condition of the spline.
Parameters | |
---|---|
velocity | initial velocity (i.e. first derivative). |
Returns | True in case of success, false otherwise. |
bool BipedalLocomotion:: Planners:: CubicSpline:: setFinalConditions(Eigen::Ref<const Eigen::VectorXd> velocity)
Set the final condition of the spline.
Parameters | |
---|---|
velocity | final velocity (i.e. first derivative). |
Returns | True in case of success, false otherwise. |
bool BipedalLocomotion:: Planners:: CubicSpline:: evaluatePoint(const std::chrono::nanoseconds& t,
Eigen::Ref<Eigen::VectorXd> position,
Eigen::Ref<Eigen::VectorXd> velocity,
Eigen::Ref<Eigen::VectorXd> acceleration) final
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:: CubicSpline:: evaluatePoint(const std::chrono::nanoseconds& t,
SplineState& state) final
Evaluate the spline at a given point.
Parameters | |
---|---|
t | instant time |
state | of the system |
Returns | True in case of success, false otherwise. |
const SplineState& BipedalLocomotion:: Planners:: CubicSpline:: getOutput() const final
Get the state of the system.
Returns | a const reference of the requested object. |
---|
bool BipedalLocomotion:: Planners:: CubicSpline:: isOutputValid() const final
Determines the validity of the object retrieved with get()
Returns | True if the object is valid, false otherwise. |
---|