robotoc
robotoc - efficient ROBOT Optimal Control solvers
|
Impact stage computations for optimal control problems. More...
#include <impact_stage.hpp>
Public Member Functions | |
ImpactStage (const std::shared_ptr< CostFunction > &cost, const std::shared_ptr< Constraints > &constraints, const std::shared_ptr< ContactSequence > &contact_sequence) | |
Constructs the impact stage. More... | |
ImpactStage () | |
Default constructor. More... | |
~ImpactStage ()=default | |
Default destructor. More... | |
ImpactStage (const ImpactStage &)=default | |
Default copy constructor. More... | |
ImpactStage & | operator= (const ImpactStage &)=default |
Default copy assign operator. More... | |
ImpactStage (ImpactStage &&) noexcept=default | |
Default move constructor. More... | |
ImpactStage & | operator= (ImpactStage &&) noexcept=default |
Default move assign operator. More... | |
OCPData | createData (const Robot &robot) const |
Creates the data. More... | |
bool | isFeasible (Robot &robot, const GridInfo &grid_info, const SplitSolution &s, OCPData &data) const |
Checks whether the solution is feasible under inequality constraints. More... | |
void | initConstraints (Robot &robot, const GridInfo &grid_info, const SplitSolution &s, OCPData &data) const |
Initializes the constraints, i.e., set slack and dual variables. More... | |
void | evalOCP (Robot &robot, const GridInfo &grid_info, const SplitSolution &s, const SplitSolution &s_next, OCPData &data, SplitKKTResidual &kkt_residual) const |
Computes the stage cost and constraint violation. More... | |
void | evalKKT (Robot &robot, const GridInfo &grid_info, const Eigen::VectorXd &q_prev, const SplitSolution &s, const SplitSolution &s_next, OCPData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual) const |
Computes the KKT residual and matrix of this stage. More... | |
void | expandPrimal (const GridInfo &grid_info, OCPData &data, SplitDirection &d) const |
Expands the condensed primal variables, i.e., computes the Newton direction of the condensed primal variables of this stage. More... | |
void | expandDual (const GridInfo &grid_info, OCPData &data, const SplitDirection &d_next, SplitDirection &d) const |
Expands the condensed dual variables, i.e., computes the Newton direction of the condensed dual variables of this stage. More... | |
double | maxPrimalStepSize (const OCPData &data) const |
Returns maximum stap size of the primal variables that satisfies the inequality constraints. More... | |
double | maxDualStepSize (const OCPData &data) const |
Returns maximum stap size of the dual variables that satisfies the inequality constraints. More... | |
void | updatePrimal (const Robot &robot, const double primal_step_size, const SplitDirection &d, SplitSolution &s, OCPData &data) const |
Updates primal variables of this stage. More... | |
void | updateDual (const double dual_step_size, OCPData &data) const |
Updates dual variables of this stage. More... | |
Impact stage computations for optimal control problems.
robotoc::ImpactStage::ImpactStage | ( | const std::shared_ptr< CostFunction > & | cost, |
const std::shared_ptr< Constraints > & | constraints, | ||
const std::shared_ptr< ContactSequence > & | contact_sequence | ||
) |
Constructs the impact stage.
[in] | cost | Shared ptr to the cost function. |
[in] | constraints | Shared ptr to the constraints. |
[in] | contact_sequence | Shared ptr to the contact sequence. |
robotoc::ImpactStage::ImpactStage | ( | ) |
Default constructor.
|
default |
Default destructor.
|
default |
Default copy constructor.
|
defaultnoexcept |
Default move constructor.
Creates the data.
[in] | robot | Robot model. |
void robotoc::ImpactStage::evalKKT | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const Eigen::VectorXd & | q_prev, | ||
const SplitSolution & | s, | ||
const SplitSolution & | s_next, | ||
OCPData & | data, | ||
SplitKKTMatrix & | kkt_matrix, | ||
SplitKKTResidual & | kkt_residual | ||
) | const |
Computes the KKT residual and matrix of this stage.
[in,out] | robot | Robot model. |
[in] | grid_info | Grid info of this stage. |
[in] | q_prev | Configuration at the previous stage. |
[in] | s | Split solution of this stage. |
[in] | s_next | Split solution of the next stage. |
[in,out] | data | Data of this stage. |
[in,out] | kkt_matrix | KKT matrix of this stage. |
[in,out] | kkt_residual | KKT residual of this stage. |
void robotoc::ImpactStage::evalOCP | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const SplitSolution & | s, | ||
const SplitSolution & | s_next, | ||
OCPData & | data, | ||
SplitKKTResidual & | kkt_residual | ||
) | const |
Computes the stage cost and constraint violation.
[in,out] | robot | Robot model. |
[in] | grid_info | Grid info of this stage. |
[in] | s | Split solution of this stage. |
[in] | s_next | Split solution of the next stage. |
[in,out] | data | Data of this stage. |
[in,out] | kkt_residual | KKT residual of this stage. |
void robotoc::ImpactStage::expandDual | ( | const GridInfo & | grid_info, |
OCPData & | data, | ||
const SplitDirection & | d_next, | ||
SplitDirection & | d | ||
) | const |
Expands the condensed dual variables, i.e., computes the Newton direction of the condensed dual variables of this stage.
[in] | grid_info | Grid info of this stage. |
[in,out] | data | Data of this stage. |
[in] | d_next | Split direction of the next stage. |
[in,out] | d | Split direction of this stage. |
void robotoc::ImpactStage::expandPrimal | ( | const GridInfo & | grid_info, |
OCPData & | data, | ||
SplitDirection & | d | ||
) | const |
Expands the condensed primal variables, i.e., computes the Newton direction of the condensed primal variables of this stage.
[in] | grid_info | Grid info of this stage. |
[in,out] | data | Data of this stage. |
[in,out] | d | Split direction of this stage. |
void robotoc::ImpactStage::initConstraints | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const SplitSolution & | s, | ||
OCPData & | data | ||
) | const |
Initializes the constraints, i.e., set slack and dual variables.
[in,out] | robot | Robot model. |
[in] | grid_info | Grid info of this stage. |
[in] | s | Split solution of this stage. |
[in,out] | data | Data of this stage. |
bool robotoc::ImpactStage::isFeasible | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const SplitSolution & | s, | ||
OCPData & | data | ||
) | const |
Checks whether the solution is feasible under inequality constraints.
[in,out] | robot | Robot model. |
[in] | grid_info | Grid info of this stage. |
[in] | s | Split solution of this stage. |
[in,out] | data | Data of this stage. |
double robotoc::ImpactStage::maxDualStepSize | ( | const OCPData & | data | ) | const |
Returns maximum stap size of the dual variables that satisfies the inequality constraints.
[in] | data | Data of this stage. |
double robotoc::ImpactStage::maxPrimalStepSize | ( | const OCPData & | data | ) | const |
Returns maximum stap size of the primal variables that satisfies the inequality constraints.
[in] | data | Data of this stage. |
|
default |
Default copy assign operator.
|
defaultnoexcept |
Default move assign operator.
void robotoc::ImpactStage::updateDual | ( | const double | dual_step_size, |
OCPData & | data | ||
) | const |
Updates dual variables of this stage.
[in] | dual_step_size | Dual step size. |
[in,out] | data | Data of this stage. |
void robotoc::ImpactStage::updatePrimal | ( | const Robot & | robot, |
const double | primal_step_size, | ||
const SplitDirection & | d, | ||
SplitSolution & | s, | ||
OCPData & | data | ||
) | const |
Updates primal variables of this stage.
[in] | robot | Robot model. |
[in] | primal_step_size | Primal step size. |
[in] | d | Split direction of this stage. |
[in,out] | s | Split solution of this stage. |
[in,out] | data | Data of this stage. |