robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
impact_stage.hpp
Go to the documentation of this file.
1#ifndef ROBOTOC_IMPACT_STAGE_HPP_
2#define ROBOTOC_IMPACT_STAGE_HPP_
3
4#include <memory>
5
6#include "Eigen/Core"
7
19
20
21namespace robotoc {
22
28public:
35 ImpactStage(const std::shared_ptr<CostFunction>& cost,
36 const std::shared_ptr<Constraints>& constraints,
37 const std::shared_ptr<ContactSequence>& contact_sequence);
38
43
47 ~ImpactStage() = default;
48
52 ImpactStage(const ImpactStage&) = default;
53
57 ImpactStage& operator=(const ImpactStage&) = default;
58
62 ImpactStage(ImpactStage&&) noexcept = default;
63
67 ImpactStage& operator=(ImpactStage&&) noexcept = default;
68
73 OCPData createData(const Robot& robot) const;
74
82 bool isFeasible(Robot& robot, const GridInfo& grid_info,
83 const SplitSolution& s, OCPData& data) const;
84
92 void initConstraints(Robot& robot, const GridInfo& grid_info,
93 const SplitSolution& s, OCPData& data) const;
94
104 void evalOCP(Robot& robot, const GridInfo& grid_info, const SplitSolution& s,
105 const SplitSolution& s_next, OCPData& data,
106 SplitKKTResidual& kkt_residual) const;
107
119 void evalKKT(Robot& robot, const GridInfo& grid_info,
120 const Eigen::VectorXd& q_prev, const SplitSolution& s,
121 const SplitSolution& s_next, OCPData& data,
122 SplitKKTMatrix& kkt_matrix, SplitKKTResidual& kkt_residual) const;
123
131 void expandPrimal(const GridInfo& grid_info, OCPData& data, SplitDirection& d) const;
132
141 void expandDual(const GridInfo& grid_info, OCPData& data,
142 const SplitDirection& d_next,
143 SplitDirection& d) const;
144
152 double maxPrimalStepSize(const OCPData& data) const;
153
161 double maxDualStepSize(const OCPData& data) const;
162
171 void updatePrimal(const Robot& robot, const double primal_step_size,
172 const SplitDirection& d, SplitSolution& s, OCPData& data) const;
173
179 void updateDual(const double dual_step_size, OCPData& data) const;
180
181private:
182 std::shared_ptr<CostFunction> cost_;
183 std::shared_ptr<Constraints> constraints_;
184 std::shared_ptr<ContactSequence> contact_sequence_;
185};
186
187} // namespace robotoc
188
189#endif // ROBOTOC_IMPACT_STAGE_HPP_
Stack of the inequality constraints. Composed by constraint components that inherits ConstraintCompon...
Definition: constraints.hpp:30
The sequence of contact status and discrete events (impact and lift).
Definition: contact_sequence.hpp:23
Stack of the cost function. Composed by cost function components that inherits CostFunctionComponentB...
Definition: cost_function.hpp:30
Impact stage computations for optimal control problems.
Definition: impact_stage.hpp:27
void updateDual(const double dual_step_size, OCPData &data) const
Updates dual variables of this stage.
double maxDualStepSize(const OCPData &data) const
Returns maximum stap size of the dual variables that satisfies the inequality constraints.
ImpactStage(const std::shared_ptr< CostFunction > &cost, const std::shared_ptr< Constraints > &constraints, const std::shared_ptr< ContactSequence > &contact_sequence)
Constructs the impact stage.
~ImpactStage()=default
Default destructor.
double maxPrimalStepSize(const OCPData &data) const
Returns maximum stap size of the primal variables that satisfies the inequality constraints.
void updatePrimal(const Robot &robot, const double primal_step_size, const SplitDirection &d, SplitSolution &s, OCPData &data) const
Updates primal variables of this stage.
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.
OCPData createData(const Robot &robot) const
Creates the data.
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 v...
ImpactStage(ImpactStage &&) noexcept=default
Default move constructor.
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.
void initConstraints(Robot &robot, const GridInfo &grid_info, const SplitSolution &s, OCPData &data) const
Initializes the constraints, i.e., set slack and dual variables.
bool isFeasible(Robot &robot, const GridInfo &grid_info, const SplitSolution &s, OCPData &data) const
Checks whether the solution is feasible under inequality constraints.
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 varia...
ImpactStage & operator=(const ImpactStage &)=default
Default copy assign operator.
ImpactStage(const ImpactStage &)=default
Default copy constructor.
ImpactStage()
Default constructor.
Dynamics and kinematics model of robots. Wraps pinocchio::Model and pinocchio::Data....
Definition: robot.hpp:32
Newton direction of the solution to the optimal control problem split into a time stage.
Definition: split_direction.hpp:20
The KKT matrix split into a time stage.
Definition: split_kkt_matrix.hpp:18
KKT residual split into each time stage.
Definition: split_kkt_residual.hpp:18
Solution to the optimal control problem split into a time stage.
Definition: split_solution.hpp:20
Definition: constraint_component_base.hpp:17
Grid information.
Definition: grid_info.hpp:24
A data structure for an optimal control problem.
Definition: ocp_data.hpp:18