robotoc
robotoc - efficient ROBOT Optimal Control solvers
|
The intermediate stage of OCP computation for unconstrained rigid-body systems. More...
#include <unconstr_intermediate_stage.hpp>
Public Member Functions | |
UnconstrIntermediateStage (const Robot &robot, const std::shared_ptr< CostFunction > &cost, const std::shared_ptr< Constraints > &constraints) | |
Constructs a split optimal control problem. More... | |
UnconstrIntermediateStage () | |
Default constructor. More... | |
~UnconstrIntermediateStage ()=default | |
Default destructor. More... | |
UnconstrIntermediateStage (const UnconstrIntermediateStage &)=default | |
Default copy constructor. More... | |
UnconstrIntermediateStage & | operator= (const UnconstrIntermediateStage &)=default |
Default copy assign operator. More... | |
UnconstrIntermediateStage (UnconstrIntermediateStage &&) noexcept=default | |
Default move constructor. More... | |
UnconstrIntermediateStage & | operator= (UnconstrIntermediateStage &&) noexcept=default |
Default move assign operator. More... | |
UnconstrOCPData | createData (const Robot &robot) const |
Creates the data. More... | |
bool | isFeasible (Robot &robot, const GridInfo &grid_info, const SplitSolution &s, UnconstrOCPData &data) const |
Checks whether the solution is feasible under inequality constraints. More... | |
void | initConstraints (Robot &robot, const GridInfo &grid_info, const SplitSolution &s, UnconstrOCPData &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, UnconstrOCPData &data, SplitKKTResidual &kkt_residual) const |
Computes the stage cost and constraint violation of this stage. More... | |
void | evalKKT (Robot &robot, const GridInfo &grid_info, const SplitSolution &s, const SplitSolution &s_next, UnconstrOCPData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual) const |
Computes the KKT matrix and residual of this stage. More... | |
void | expandPrimalAndDual (const double dt, const SplitKKTMatrix &kkt_matrix, const SplitKKTResidual &kkt_residual, UnconstrOCPData &data, SplitDirection &d) const |
Expands the primal and dual variables, i.e., computes the Newton direction of the condensed variables of this stage. More... | |
double | maxPrimalStepSize (const UnconstrOCPData &data) const |
Computes the maximum primal step size. More... | |
double | maxDualStepSize (const UnconstrOCPData &data) const |
Computes the maximum dual size. More... | |
void | updatePrimal (const Robot &robot, const double primal_step_size, const SplitDirection &d, SplitSolution &s, UnconstrOCPData &data) const |
Updates primal variables of this stage. More... | |
void | updateDual (const double dual_step_size, UnconstrOCPData &data) const |
Updates dual variables of the inequality constraints. More... | |
The intermediate stage of OCP computation for unconstrained rigid-body systems.
The terminal stage of OCP computation for unconstrained rigid-body systems.
robotoc::UnconstrIntermediateStage::UnconstrIntermediateStage | ( | const Robot & | robot, |
const std::shared_ptr< CostFunction > & | cost, | ||
const std::shared_ptr< Constraints > & | constraints | ||
) |
Constructs a split optimal control problem.
[in] | robot | Robot model. |
[in] | cost | Shared ptr to the cost function. |
[in] | constraints | Shared ptr to the constraints. |
robotoc::UnconstrIntermediateStage::UnconstrIntermediateStage | ( | ) |
Default constructor.
|
default |
Default destructor.
|
default |
Default copy constructor.
|
defaultnoexcept |
Default move constructor.
UnconstrOCPData robotoc::UnconstrIntermediateStage::createData | ( | const Robot & | robot | ) | const |
Creates the data.
[in] | robot | Robot model. |
void robotoc::UnconstrIntermediateStage::evalKKT | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const SplitSolution & | s, | ||
const SplitSolution & | s_next, | ||
UnconstrOCPData & | data, | ||
SplitKKTMatrix & | kkt_matrix, | ||
SplitKKTResidual & | kkt_residual | ||
) | const |
Computes the KKT matrix and residual of this stage.
[in,out] | robot | Robot model. |
[in] | grid_info | Grid info. |
[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 | Split KKT matrix of this stage. |
[in,out] | kkt_residual | Split KKT residual of this stage. |
void robotoc::UnconstrIntermediateStage::evalOCP | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const SplitSolution & | s, | ||
const SplitSolution & | s_next, | ||
UnconstrOCPData & | data, | ||
SplitKKTResidual & | kkt_residual | ||
) | const |
Computes the stage cost and constraint violation of this stage.
[in,out] | robot | Robot model. |
[in] | grid_info | Grid info. |
[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 | Split KKT residual of this stage. |
void robotoc::UnconstrIntermediateStage::expandPrimalAndDual | ( | const double | dt, |
const SplitKKTMatrix & | kkt_matrix, | ||
const SplitKKTResidual & | kkt_residual, | ||
UnconstrOCPData & | data, | ||
SplitDirection & | d | ||
) | const |
Expands the primal and dual variables, i.e., computes the Newton direction of the condensed variables of this stage.
[in] | dt | Time step. |
[in] | kkt_matrix | Split KKT matrix of this stage. |
[in] | kkt_residual | Split KKT residual of this stage. |
[in,out] | data | Data of this stage. |
[in,out] | d | Split direction of this stage. |
void robotoc::UnconstrIntermediateStage::initConstraints | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const SplitSolution & | s, | ||
UnconstrOCPData & | data | ||
) | const |
Initializes the constraints, i.e., set slack and dual variables.
[in,out] | robot | Robot model. |
[in] | grid_info | Grid info. |
[in] | s | Split solution of this stage. |
[in,out] | data | Data of this stage. |
bool robotoc::UnconstrIntermediateStage::isFeasible | ( | Robot & | robot, |
const GridInfo & | grid_info, | ||
const SplitSolution & | s, | ||
UnconstrOCPData & | 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::UnconstrIntermediateStage::maxDualStepSize | ( | const UnconstrOCPData & | data | ) | const |
Computes the maximum dual size.
[in] | data | Data of this stage. |
double robotoc::UnconstrIntermediateStage::maxPrimalStepSize | ( | const UnconstrOCPData & | data | ) | const |
Computes the maximum primal step size.
[in] | data | Data of this stage. |
|
default |
Default copy assign operator.
|
defaultnoexcept |
Default move assign operator.
void robotoc::UnconstrIntermediateStage::updateDual | ( | const double | dual_step_size, |
UnconstrOCPData & | data | ||
) | const |
Updates dual variables of the inequality constraints.
[in] | dual_step_size | Dula step size. |
[in,out] | data | Data of this stage. |
void robotoc::UnconstrIntermediateStage::updatePrimal | ( | const Robot & | robot, |
const double | primal_step_size, | ||
const SplitDirection & | d, | ||
SplitSolution & | s, | ||
UnconstrOCPData & | 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. |