robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
robotoc::ImpactStage Class Reference

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...
 
ImpactStageoperator= (const ImpactStage &)=default
 Default copy assign operator. More...
 
 ImpactStage (ImpactStage &&) noexcept=default
 Default move constructor. More...
 
ImpactStageoperator= (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...
 

Detailed Description

Impact stage computations for optimal control problems.

Constructor & Destructor Documentation

◆ ImpactStage() [1/4]

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.

Parameters
[in]costShared ptr to the cost function.
[in]constraintsShared ptr to the constraints.
[in]contact_sequenceShared ptr to the contact sequence.

◆ ImpactStage() [2/4]

robotoc::ImpactStage::ImpactStage ( )

Default constructor.

◆ ~ImpactStage()

robotoc::ImpactStage::~ImpactStage ( )
default

Default destructor.

◆ ImpactStage() [3/4]

robotoc::ImpactStage::ImpactStage ( const ImpactStage )
default

Default copy constructor.

◆ ImpactStage() [4/4]

robotoc::ImpactStage::ImpactStage ( ImpactStage &&  )
defaultnoexcept

Default move constructor.

Member Function Documentation

◆ createData()

OCPData robotoc::ImpactStage::createData ( const Robot robot) const

Creates the data.

Parameters
[in]robotRobot model.

◆ evalKKT()

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.

Parameters
[in,out]robotRobot model.
[in]grid_infoGrid info of this stage.
[in]q_prevConfiguration at the previous stage.
[in]sSplit solution of this stage.
[in]s_nextSplit solution of the next stage.
[in,out]dataData of this stage.
[in,out]kkt_matrixKKT matrix of this stage.
[in,out]kkt_residualKKT residual of this stage.

◆ evalOCP()

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.

Parameters
[in,out]robotRobot model.
[in]grid_infoGrid info of this stage.
[in]sSplit solution of this stage.
[in]s_nextSplit solution of the next stage.
[in,out]dataData of this stage.
[in,out]kkt_residualKKT residual of this stage.

◆ expandDual()

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.

Parameters
[in]grid_infoGrid info of this stage.
[in,out]dataData of this stage.
[in]d_nextSplit direction of the next stage.
[in,out]dSplit direction of this stage.

◆ expandPrimal()

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.

Parameters
[in]grid_infoGrid info of this stage.
[in,out]dataData of this stage.
[in,out]dSplit direction of this stage.

◆ initConstraints()

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.

Parameters
[in,out]robotRobot model.
[in]grid_infoGrid info of this stage.
[in]sSplit solution of this stage.
[in,out]dataData of this stage.

◆ isFeasible()

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.

Parameters
[in,out]robotRobot model.
[in]grid_infoGrid info of this stage.
[in]sSplit solution of this stage.
[in,out]dataData of this stage.

◆ maxDualStepSize()

double robotoc::ImpactStage::maxDualStepSize ( const OCPData data) const

Returns maximum stap size of the dual variables that satisfies the inequality constraints.

Parameters
[in]dataData of this stage.
Returns
Maximum stap size of the dual variables that satisfies the inequality constraints.

◆ maxPrimalStepSize()

double robotoc::ImpactStage::maxPrimalStepSize ( const OCPData data) const

Returns maximum stap size of the primal variables that satisfies the inequality constraints.

Parameters
[in]dataData of this stage.
Returns
Maximum stap size of the primal variables that satisfies the inequality constraints.

◆ operator=() [1/2]

ImpactStage & robotoc::ImpactStage::operator= ( const ImpactStage )
default

Default copy assign operator.

◆ operator=() [2/2]

ImpactStage & robotoc::ImpactStage::operator= ( ImpactStage &&  )
defaultnoexcept

Default move assign operator.

◆ updateDual()

void robotoc::ImpactStage::updateDual ( const double  dual_step_size,
OCPData data 
) const

Updates dual variables of this stage.

Parameters
[in]dual_step_sizeDual step size.
[in,out]dataData of this stage.

◆ updatePrimal()

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.

Parameters
[in]robotRobot model.
[in]primal_step_sizePrimal step size.
[in]dSplit direction of this stage.
[in,out]sSplit solution of this stage.
[in,out]dataData of this stage.

The documentation for this class was generated from the following file: