robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
robotoc Namespace Reference

Namespaces

namespace  benchmark
 
namespace  constraintsimpl
 
namespace  numerics
 
namespace  pdipm
 
namespace  rotation
 

Classes

class  BackwardRiccatiRecursionFactorizer
 Factorizer of the backward Riccati recursion. More...
 
class  BipedWalkFootStepPlanner
 Foot step planner for the biped robot walk. More...
 
class  CoMCost
 Cost on the position of the center of mass. More...
 
class  CoMRefBase
 Base class of reference position of the center of mass (CoM). More...
 
class  ConfigurationSpaceCost
 Configuration space cost. More...
 
class  ConfigurationSpaceRefBase
 Base class of the configuration. More...
 
class  ConstraintComponentBase
 Base class for constraint components. More...
 
class  ConstraintComponentData
 Data used in constraint components. Composed by slack, dual (Lagrange multiplier), primal residual, complementary slackness between the slack and dual, and directions of slack and dual. More...
 
class  Constraints
 Stack of the inequality constraints. Composed by constraint components that inherits ConstraintComponentBase or ImpactConstraintComponentBase. More...
 
class  ConstraintsData
 Data for constraints. Composed of ConstraintComponentData corrensponding to the components of Constraints. More...
 
class  ContactDynamicsData
 Data used in ContactDynamics. More...
 
class  ContactModelInfo
 Info of a contact model. More...
 
class  ContactPlannerBase
 Base interface of contact planners. More...
 
class  ContactSequence
 The sequence of contact status and discrete events (impact and lift). More...
 
class  ContactStatus
 Contact status of robot model. More...
 
class  ContactWrenchCone
 Constraint on the contact wrench cone for surface contacts. More...
 
class  ControlPolicy
 Control pocily constructed for the MPC solution. More...
 
class  CostFunction
 Stack of the cost function. Composed by cost function components that inherits CostFunctionComponentBase. More...
 
class  CostFunctionComponentBase
 Base class of components of cost function. More...
 
class  CostFunctionData
 Composed of data used to compute the cost function and its derivatives. More...
 
class  CrawlFootStepPlanner
 Foot step planner for the crawl gait of quadrupeds. More...
 
class  DerivativeChecker
 
class  DirectMultipleShooting
 Direct multiple shooting method of the optimal control problems. More...
 
class  DiscreteEvent
 Discrete event composed by impact and lift. More...
 
class  DiscreteTimeCoMRef
 Discrete-time reference of the center of mass. More...
 
class  DiscreteTimeSwingFootRef
 Discrete-time reference of the positions of swinging contact frames. More...
 
class  FlyingTrotFootStepPlanner
 Foot step planner for the flying trot gait of quadrupeds. More...
 
class  FrictionCone
 Constraint on the inner-approximated firction cone. More...
 
class  GridInfo
 Grid information. More...
 
class  ImpactConstraintComponentBase
 Base class for impact constraint components. More...
 
class  ImpactFrictionCone
 Constraint on the inner-approximated impact firction cone. More...
 
class  ImpactStage
 Impact stage computations for optimal control problems. More...
 
class  ImpactStatus
 Impact status of robot model. Wrapper of ContactStatus to treat impacts. More...
 
class  ImpactWrenchCone
 Constraint on the wrench firction cone for surface contacts. More...
 
class  IntermediateStage
 Intermediate stage computations for optimal control problems. More...
 
class  JointAccelerationLowerLimit
 Constraint on the lower limits of the joint acceleration. More...
 
class  JointAccelerationUpperLimit
 Constraint on the upper limits of the joint acceleration. More...
 
class  JointPositionLowerLimit
 Constraint on the lower limits of the joint position. More...
 
class  JointPositionUpperLimit
 Constraint on the upper limits of the joint position. More...
 
class  JointTorquesLowerLimit
 Constraint on the lower limits of the joint torques. More...
 
class  JointTorquesUpperLimit
 Constraint on the upper limits of the joint torques. More...
 
class  JointVelocityLowerLimit
 Constraint on the lower limits of the joint velocity. More...
 
class  JointVelocityUpperLimit
 Constraint on the upper limits of the joint velocity. More...
 
class  JumpFootStepPlanner
 Foot step planner for the jump motion. More...
 
class  LineSearch
 Line search for optimal control problems. More...
 
class  LineSearchFilter
 Filter of the line search. More...
 
class  LineSearchSettings
 Settings for the line search. More...
 
class  LocalContactForceCost
 Cost on the contact forces expressed in the local frames. More...
 
class  LQRPolicy
 The state feedback and feedforward policy of LQR subproblem at a time stage. More...
 
class  MovingWindowFilter
 Moving window filter for foot step planning. More...
 
class  MPCBipedWalk
 MPC solver for the bipedal robot walk. More...
 
class  MPCCrawl
 MPC solver for the crawl gait of quadrupeds. More...
 
class  MPCFlyingTrot
 MPC solver for the trot gait of quadrupeds. More...
 
class  MPCJump
 MPC solver for the jump control. More...
 
class  MPCPace
 MPC solver for the pace gait of quadrupeds. More...
 
class  MPCPeriodicCoMRef
 Periodic reference positions of the center of mass. More...
 
class  MPCPeriodicConfigurationRef
 Periodic reference configuration for MPC of legged robots. More...
 
class  MPCPeriodicSwingFootRef
 Periodic reference of the foot position. More...
 
class  MPCTrot
 MPC solver for the trot gait of quadrupeds. More...
 
class  OCP
 The optimal control problem. More...
 
class  OCPData
 A data structure for an optimal control problem. More...
 
class  OCPSolver
 Optimal control problem solver by Riccati recursion. More...
 
class  PaceFootStepPlanner
 Foot step planner for the pace gait of quadrupeds. More...
 
class  ParNMPCIntermediateStage
 The intermediate stage of ParNMPC for unconstrained rigid-body systems. More...
 
class  ParNMPCTerminalStage
 The terminal stage of ParNMPC for unconstrained rigid-body systems. More...
 
class  PerformanceIndex
 Performance index of optimal control problems. More...
 
class  PeriodicCoMRef
 Periodic reference of the center of mass. More...
 
class  PeriodicSwingFootRef
 Periodic reference of the swing foot position. More...
 
class  PointContact
 Kinematics and dynamic model of a point contact. More...
 
class  RaibertHeuristic
 Raibert heuristic for foot step planning. More...
 
class  RiccatiFactorizer
 Riccati factorizer. More...
 
class  RiccatiRecursion
 Riccati recursion solver for optimal control problems. Solves the KKT system in linear time complexity w.r.t. the length of the horizon. More...
 
class  Robot
 Dynamics and kinematics model of robots. Wraps pinocchio::Model and pinocchio::Data. Includes contacts. More...
 
class  RobotModelInfo
 Info of a robot model. More...
 
class  RobotProperties
 Collection of the robot properties, which can change after constructing robot models. More...
 
class  SE3JacobianInverse
 A class that computes the inverse of the Jacobian of SE(3). More...
 
class  SolutionInterpolator
 Solution interpolator. More...
 
class  SolverOptions
 Options of optimal control solvers. More...
 
class  SolverStatistics
 Statistics of optimal control solvers. More...
 
class  SplitConstrainedRiccatiFactorization
 Riccati factorization matrix and vector for the switching constraint. More...
 
class  SplitDirection
 Newton direction of the solution to the optimal control problem split into a time stage. More...
 
class  SplitKKTMatrix
 The KKT matrix split into a time stage. More...
 
class  SplitKKTResidual
 KKT residual split into each time stage. More...
 
class  SplitRiccatiFactorization
 Riccati factorization matrix and vector for a time stage. More...
 
class  SplitSolution
 Solution to the optimal control problem split into a time stage. More...
 
class  StateEquationData
 Data for the state equations. More...
 
class  STOConstraints
 Constraints of the switching time optimization problems. More...
 
class  STOCostFunction
 Stack of the cost function of the switching time optimization (STO) problem. Composed by cost function components that inherits STOCostFunctionComponentBase. More...
 
class  STOCostFunctionComponentBase
 Base class of components of the cost function of the switching time optimization (STO) problem. More...
 
class  STOPolicy
 The state feedback and feedforward policy of the switching time optimization (STO). More...
 
class  SurfaceContact
 Kinematics and dynamic model of a surface contact. More...
 
class  SwitchingConstraintData
 Data for the switching constraint. More...
 
class  SwitchingTimeOptimization
 The switching time optimization (STO) problem. More...
 
class  TaskSpace3DCost
 Cost on the task space position. More...
 
class  TaskSpace3DRefBase
 Base class of reference task space position. More...
 
class  TaskSpace6DCost
 Cost on the task space placement (SE(3)). More...
 
class  TaskSpace6DRefBase
 Base class of reference task space placement (position and orientation). More...
 
class  TerminalStage
 Terminal stage computations for optimal control problems. More...
 
class  TimeDiscretization
 Time discretization of the optimal control problem. More...
 
class  Timer
 A timer class to take benchmarks. More...
 
class  TrotFootStepPlanner
 Foot step planner for the trot gait of quadrupeds. More...
 
class  TrotSwingFootRef
 Periodic reference of the foot position. More...
 
class  UnconstrBackwardCorrection
 Backward correction for optimal control problems of unconstrained rigid-body systems. More...
 
class  UnconstrBackwardRiccatiRecursionFactorizer
 Factorizer of the backward Riccati recursion of a time stage. More...
 
class  UnconstrDirectMultipleShooting
 Direct multiple shooting method of optimal control problems of unconstrained rigid-body systems. More...
 
class  UnconstrDynamics
 Inverse dynamics constraint without constraints (floating base or contacts). More...
 
class  UnconstrIntermediateStage
 The intermediate stage of OCP computation for unconstrained rigid-body systems. More...
 
class  UnconstrKKTMatrixInverter
 Schur complement for SplitKKTMatrix for UnconstrParNMPC. More...
 
class  UnconstrLineSearch
 Line search for optimal control problems for unconstrained rigid-body systems. More...
 
class  UnconstrOCPData
 Data structure for the optimal control problem of unconstrained rigid-body systems. More...
 
class  UnconstrOCPSolver
 Optimal control problem solver of unconstrained rigid-body systems by Riccati recursion. "Unconstrained" means that the system does not have either a floating base or any contacts. More...
 
class  UnconstrParNMPCSolver
 Optimal control problem solver of unconstrained rigid-body systems by ParNMPC algorithm. "Unconstrained" means that the system does not have either a floating base or any contacts. More...
 
class  UnconstrRiccatiFactorizer
 Riccati factorizer for a time stage. More...
 
class  UnconstrRiccatiRecursion
 Riccati recursion solver for optimal control problems of unconstrained rigid-body systems. More...
 
class  UnconstrSplitBackwardCorrection
 Split backward correction. More...
 
class  UnconstrTerminalStage
 

Typedefs

using Direction = aligned_vector< SplitDirection >
 Newton direction of the solution to the optimal control problem. More...
 
using KKTMatrix = aligned_vector< SplitKKTMatrix >
 The KKT matrix of the optimal control problem. More...
 
using KKTResidual = aligned_vector< SplitKKTResidual >
 The KKT residual of the optimal control problem. More...
 
using Solution = aligned_vector< SplitSolution >
 Solution to the optimal control problem. More...
 
using RiccatiFactorization = aligned_vector< SplitRiccatiFactorization >
 Riccati factorization matices of the LQR subproblem. More...
 
using UnconstrRiccatiFactorization = std::vector< SplitRiccatiFactorization >
 Riccati factorization matices of the LQR subproblem for the unconstrained optimal control problem. More...
 
using SE3 = pinocchio::SE3
 Using pinocchio::SE3 without its namespace. More...
 
template<typename T >
using aligned_deque = std::deque< T, Eigen::aligned_allocator< T > >
 std deque with Eigen::aligned_allocator. More...
 
template<typename Key , typename T >
using aligned_unordered_map = std::unordered_map< Key, T, std::hash< Key >, std::equal_to< Key >, Eigen::aligned_allocator< std::pair< Key, T > > >
 std unordered_map with Eigen::aligned_allocator. More...
 
template<typename T >
using aligned_vector = std::vector< T, Eigen::aligned_allocator< T > >
 std vector with Eigen::aligned_allocator. More...
 

Enumerations

enum class  KinematicsLevel { PositionLevel , VelocityLevel , AccelerationLevel }
 Kinematics level of the constraint component used in ConstraintComponentBase. More...
 
enum class  FootTrajectoryType { Triangle , Ellipsoid }
 Type of the foot trajectory. More...
 
enum class  LineSearchMethod { Filter , MeritBacktracking }
 Type of the line search method. More...
 
enum class  DiscretizationMethod { GridBased , PhaseBased }
 Discretization method of the optimal control problem. More...
 
enum class  GridType { Intermediate , Impact , Lift , Terminal }
 Type of the grid. More...
 
enum class  DiscreteEventType { Impact , Lift , None }
 Type of the discrete events. More...
 
enum class  ContactType { PointContact , SurfaceContact }
 Types of contacts. More...
 
enum class  BaseJointType { FixedBase , FloatingBase }
 Types of the base joints of robots. More...
 
enum class  InterpolationOrder { Linear , Zero }
 Order of the interpolation. More...
 

Functions

std::ostream & operator<< (std::ostream &os, const Direction &d)
 
std::ostream & operator<< (std::ostream &os, const KKTMatrix &kkt_matrix)
 
std::ostream & operator<< (std::ostream &os, const KKTResidual &kkt_residual)
 
std::ostream & operator<< (std::ostream &os, const Solution &s)
 
void evalContactDynamics (Robot &robot, const ContactStatus &contact_status, const SplitSolution &s, ContactDynamicsData &data)
 Computes the residual in the contact dynamics constraint. More...
 
void linearizeContactDynamics (Robot &robot, const ContactStatus &contact_status, const SplitSolution &s, ContactDynamicsData &data, SplitKKTResidual &kkt_residual)
 Computes the residual and derivatives of the contact dynamics
constraint and derivatives of it. More...
 
void condenseContactDynamics (Robot &robot, const ContactStatus &contact_status, const double dt, ContactDynamicsData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Condenses the acceleration, contact forces, and Lagrange multipliers. More...
 
void expandContactDynamicsPrimal (const ContactDynamicsData &data, SplitDirection &d)
 Expands the primal variables, i.e., computes the Newton direction of the condensed primal variables (acceleration a and the contact forces f) of this stage. More...
 
void expandContactDynamicsDual (const double dt, const double dts, ContactDynamicsData &data, const SplitDirection &d_next, SplitDirection &d)
 Expands the dual variables, i.e., computes the Newton direction of the condensed dual variables (Lagrange multipliers) of this stage. More...
 
void evalImpactDynamics (Robot &robot, const ImpactStatus &impact_status, const SplitSolution &s, ContactDynamicsData &data)
 Computes the residual in the impact dynamics constraint. More...
 
void linearizeImpactDynamics (Robot &robot, const ImpactStatus &impact_status, const SplitSolution &s, ContactDynamicsData &data, SplitKKTResidual &kkt_residual)
 Linearizes the impact dynamics constraint. More...
 
void condenseImpactDynamics (Robot &robot, const ImpactStatus &impact_status, ContactDynamicsData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Condenses the inverse dynamics constraint. More...
 
void expandImpactDynamicsPrimal (const ContactDynamicsData &data, SplitDirection &d)
 Expands the primal variables, i.e., computes the Newton direction of the condensed primal variables (impact change in the velocity dv and the impact forces f) of this impact stage. More...
 
void expandImpactDynamicsDual (ContactDynamicsData &data, const SplitDirection &d_next, SplitDirection &d)
 Expands the dual variables, i.e., computes the Newton direction of the condensed dual variables (Lagrange multipliers) of this impact stage. More...
 
void evalImpactStateEquation (const Robot &robot, const SplitSolution &s, const Eigen::VectorXd &q_next, const Eigen::VectorXd &v_next, SplitKKTResidual &kkt_residual)
 Computes the residual in the impact state equation. More...
 
void evalImpactStateEquation (const Robot &robot, const SplitSolution &s, const SplitSolution &s_next, SplitKKTResidual &kkt_residual)
 Computes the residual in the impact state equation. More...
 
void linearizeImpactStateEquation (const Robot &robot, const Eigen::VectorXd &q_prev, const SplitSolution &s, const SplitSolution &s_next, StateEquationData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Linearizes the impact state equation. More...
 
void correctLinearizeImpactStateEquation (const Robot &robot, const SplitSolution &s, const SplitSolution &s_next, StateEquationData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Corrects the linearized state equation using the Jacobian of the Lie group. More...
 
void correctCostateDirection (StateEquationData &data, SplitDirection &d)
 Corrects the costate direction using the Jacobian of the Lie group. More...
 
void evalStateEquation (const Robot &robot, const double dt, const SplitSolution &s, const Eigen::VectorXd &q_next, const Eigen::VectorXd &v_next, SplitKKTResidual &kkt_residual)
 Computes the residual in the state equation. More...
 
void evalStateEquation (const Robot &robot, const double dt, const SplitSolution &s, const SplitSolution &s_next, SplitKKTResidual &kkt_residual)
 Computes the residual in the state equation. More...
 
void linearizeStateEquation (const Robot &robot, const double dt, const Eigen::VectorXd &q_prev, const SplitSolution &s, const SplitSolution &s_next, StateEquationData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Linearizes the state equation. More...
 
void correctLinearizeStateEquation (const Robot &robot, const double dt, const SplitSolution &s, const SplitSolution &s_next, StateEquationData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Corrects the linearized state equation using the Jacobian of the Lie group. More...
 
void computeInitialStateDirection (const Robot &robot, const Eigen::VectorXd &q0, const Eigen::VectorXd &v0, const SplitSolution &s0, const StateEquationData &data, SplitDirection &d0)
 Computes the initial state direction using the result of
linearizeStateEquation() and correctLinearizeStateEquation(). More...
 
void evalSwitchingConstraint (Robot &robot, const ImpactStatus &impact_status, SwitchingConstraintData &data, const double dt1, const double dt2, const SplitSolution &s, SplitKKTResidual &kkt_residual)
 Computes the residual in the switching constraint, i.e., the contact position constraint. More...
 
void linearizeSwitchingConstraint (Robot &robot, const ImpactStatus &impact_status, SwitchingConstraintData &data, const double dt1, const double dt2, const SplitSolution &s, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Linearizes the switching constraint, i.e., the contact position constraint. More...
 
void linearizeTerminalStateEquation (const Robot &robot, const Eigen::VectorXd &q_prev, const SplitSolution &s, StateEquationData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Linearizes the state equation at the teminal stage. More...
 
void correctLinearizeTerminalStateEquation (StateEquationData &data, SplitKKTMatrix &kkt_matrix)
 Corrects the linearized state equation using the Jacobian of the Lie group. More...
 
void linearizeUnconstrForwardEuler (const double dt, const SplitSolution &s, const SplitSolution &s_next, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Linearizes the state equation of forward Euler. More...
 
void linearizeUnconstrForwardEulerTerminal (const SplitSolution &s, SplitKKTResidual &kkt_residual)
 Linearizes the state equation of forward Euler. More...
 
void linearizeUnconstrBackwardEuler (const double dt, const Eigen::VectorXd &q_prev, const Eigen::VectorXd &v_prev, const SplitSolution &s, const SplitSolution &s_next, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Linearizes the state equation of backward Euler. More...
 
void linearizeUnconstrBackwardEulerTerminal (const double dt, const Eigen::VectorXd &q_prev, const Eigen::VectorXd &v_prev, const SplitSolution &s, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
 Linearizes the state equation of backward Euler at the terminal stage. More...
 
void evalUnconstrForwardEuler (const double dt, const SplitSolution &s, const SplitSolution &s_next, SplitKKTResidual &kkt_residual)
 Computes the residual in the state equation of forward Euler. More...
 
void evalUnconstrBackwardEuler (const double dt, const Eigen::VectorXd &q_prev, const Eigen::VectorXd &v_prev, const SplitSolution &s, SplitKKTResidual &kkt_residual)
 Computes the residual in the state equation of backward Euler. More...
 
void computeInitialStateDirection (const Robot &robot, const Eigen::VectorXd &q0, const Eigen::VectorXd &v0, const SplitSolution &s0, const OCPData &data, SplitDirection &d0)
 Computes the initial state direction using the result of
IntermediateStage::evalKKT(). More...
 
std::ostream & operator<< (std::ostream &os, const RiccatiFactorization &riccati)
 
void forwardRiccatiRecursion (const SplitKKTMatrix &kkt_matrix, const SplitKKTResidual &kkt_residual, const LQRPolicy &lqr_policy, SplitDirection &d, SplitDirection &d_next, const bool sto, const bool has_next_sto_phase)
 Performs the forward Riccati recursion and computes the state direction. More...
 
void forwardRiccatiRecursion (const SplitKKTMatrix &kkt_matrix, const SplitKKTResidual &kkt_residual, const SplitDirection &d, SplitDirection &d_next)
 Performs the forward Riccati recursion and computes the state direction. More...
 
void computeSwitchingTimeDirection (const STOPolicy &sto_policy, SplitDirection &d, const bool has_prev_sto_phase)
 Computes the switching time direction. More...
 
void computeCostateDirection (const SplitRiccatiFactorization &riccati, SplitDirection &d, const bool sto, const bool has_next_sto_phase)
 Computes the Newton direction of the costate. More...
 
void computeCostateDirection (const SplitRiccatiFactorization &riccati, SplitDirection &d, const bool sto)
 Computes the Newton direction of the costate. More...
 
void computeLagrangeMultiplierDirection (const SplitRiccatiFactorization &riccati, SplitDirection &d, const bool sto, const bool has_next_sto_phase)
 Computes the Newton direction of the Lagrange multiplier with respect to the switching constraint. More...
 
template<typename SE3Type >
const Eigen::Matrix< double, 6, 1 > Log6Map (const SE3Type &SE3_obj)
 Applies Log6 map that transforms the SE3 into 6-dimensional vector. More...
 
template<typename SE3Type , typename MatrixType >
void computeJLog6Map (const SE3Type &SE3_obj, const Eigen::MatrixBase< MatrixType > &J)
 Computes the Jacobian of the Log6 map. More...
 

Typedef Documentation

◆ aligned_deque

template<typename T >
robotoc::aligned_deque

std deque with Eigen::aligned_allocator.

◆ aligned_unordered_map

template<typename Key , typename T >
robotoc::aligned_unordered_map

std unordered_map with Eigen::aligned_allocator.

◆ aligned_vector

template<typename T >
robotoc::aligned_vector

std vector with Eigen::aligned_allocator.

◆ Direction

Newton direction of the solution to the optimal control problem.

◆ KKTMatrix

The KKT matrix of the optimal control problem.

◆ KKTResidual

The KKT residual of the optimal control problem.

◆ RiccatiFactorization

Riccati factorization matices of the LQR subproblem.

◆ SE3

Using pinocchio::SE3 without its namespace.

◆ Solution

Solution to the optimal control problem.

◆ UnconstrRiccatiFactorization

Riccati factorization matices of the LQR subproblem for the unconstrained optimal control problem.

Enumeration Type Documentation

◆ BaseJointType

enum class robotoc::BaseJointType
strong

Types of the base joints of robots.

Enumerator
FixedBase 
FloatingBase 

◆ ContactType

enum class robotoc::ContactType
strong

Types of contacts.

Enumerator
PointContact 
SurfaceContact 

◆ DiscreteEventType

enum class robotoc::DiscreteEventType
strong

Type of the discrete events.

Enumerator
Impact 
Lift 
None 

◆ DiscretizationMethod

enum class robotoc::DiscretizationMethod
strong

Discretization method of the optimal control problem.

Enumerator
GridBased 
PhaseBased 

◆ FootTrajectoryType

enum class robotoc::FootTrajectoryType
strong

Type of the foot trajectory.

Enumerator
Triangle 
Ellipsoid 

◆ GridType

enum class robotoc::GridType
strong

Type of the grid.

Enumerator
Intermediate 
Impact 
Lift 
Terminal 

◆ InterpolationOrder

enum class robotoc::InterpolationOrder
strong

Order of the interpolation.

Enumerator
Linear 
Zero 

◆ KinematicsLevel

enum class robotoc::KinematicsLevel
strong

Kinematics level of the constraint component used in ConstraintComponentBase.

Enumerator
PositionLevel 
VelocityLevel 
AccelerationLevel 

◆ LineSearchMethod

enum class robotoc::LineSearchMethod
strong

Type of the line search method.

Enumerator
Filter 
MeritBacktracking 

Function Documentation

◆ computeCostateDirection() [1/2]

void robotoc::computeCostateDirection ( const SplitRiccatiFactorization riccati,
SplitDirection d,
const bool  sto 
)

Computes the Newton direction of the costate.

Parameters
[in]riccatiRiccati factorization of this impact stage.
[in,out]dImpact split direction.
[in]stoIf true, the STO sensitivities are also considered.

◆ computeCostateDirection() [2/2]

void robotoc::computeCostateDirection ( const SplitRiccatiFactorization riccati,
SplitDirection d,
const bool  sto,
const bool  has_next_sto_phase 
)

Computes the Newton direction of the costate.

Parameters
[in]riccatiRiccati factorization of this impact stage.
[in,out]dSplit direction.
[in]stoIf true, the STO sensitivities are also considered.
[in]has_next_sto_phaseFlag for wheather this phase has the next phase involving the STO problem.

◆ computeInitialStateDirection() [1/2]

void robotoc::computeInitialStateDirection ( const Robot robot,
const Eigen::VectorXd &  q0,
const Eigen::VectorXd &  v0,
const SplitSolution s0,
const OCPData data,
SplitDirection d0 
)

Computes the initial state direction using the result of
IntermediateStage::evalKKT().

Parameters
[in]robotRobot model.
[in]q0Initial configuration.
[in]v0Initial generalized velocity.
[in]s0Split solution at the initial stage.
[in]dataData structure for the optimal control problem.
[in,out]d0Split direction at the initial stage.

◆ computeInitialStateDirection() [2/2]

void robotoc::computeInitialStateDirection ( const Robot robot,
const Eigen::VectorXd &  q0,
const Eigen::VectorXd &  v0,
const SplitSolution s0,
const StateEquationData data,
SplitDirection d0 
)

Computes the initial state direction using the result of
linearizeStateEquation() and correctLinearizeStateEquation().

Parameters
[in]robotRobot model.
[in]q0Initial configuration.
[in]v0Initial generalized velocity.
[in]s0Split solution at the initial stage.
[in]dataData structure for the state equation.
[in,out]d0Split direction at the initial stage.

◆ computeJLog6Map()

template<typename SE3Type , typename MatrixType >
void robotoc::computeJLog6Map ( const SE3Type &  SE3_obj,
const Eigen::MatrixBase< MatrixType > &  J 
)

Computes the Jacobian of the Log6 map.

Parameters
[in]SE3_objSE3 object
[in,out]JResultant Jacobian. Size must be 6x6.

◆ computeLagrangeMultiplierDirection()

void robotoc::computeLagrangeMultiplierDirection ( const SplitRiccatiFactorization riccati,
SplitDirection d,
const bool  sto,
const bool  has_next_sto_phase 
)

Computes the Newton direction of the Lagrange multiplier with respect to the switching constraint.

Parameters
[in]riccatiRiccati factorization.
[in,out]dSplit direction of the this stage.
[in]stoIf true, the STO sensitivities are also considered.
[in]has_next_sto_phaseFlag for wheather this phase has the next phase involving the STO problem.

◆ computeSwitchingTimeDirection()

void robotoc::computeSwitchingTimeDirection ( const STOPolicy sto_policy,
SplitDirection d,
const bool  has_prev_sto_phase 
)

Computes the switching time direction.

Parameters
[in,out]sto_policySTO policy.
[in]dSplit direction.
[in]has_prev_sto_phaseFlag for wheather this phase has the previous phase involving the STO problem.

◆ condenseContactDynamics()

void robotoc::condenseContactDynamics ( Robot robot,
const ContactStatus contact_status,
const double  dt,
ContactDynamicsData data,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Condenses the acceleration, contact forces, and Lagrange multipliers.

Parameters
[in]robotRobot model.
[in]contact_statusContact status of this time stage.
[in]dtTime step of this time stage.
[in,out]dataData structure for the contact dynamics.
[in,out]kkt_matrixSplit KKT matrix of this time stage.
[in,out]kkt_residualSplit KKT residual of this time stage.

◆ condenseImpactDynamics()

void robotoc::condenseImpactDynamics ( Robot robot,
const ImpactStatus impact_status,
ContactDynamicsData data,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Condenses the inverse dynamics constraint.

Parameters
[in]robotRobot model.
[in]impact_statusImpact status of this impact stage.
[in,out]dataData structure for the contact dynamics.
[in,out]kkt_matrixSplit KKT matrix of this impact stage.
[in,out]kkt_residualSplit KKT residual of this impact stage.

◆ correctCostateDirection()

void robotoc::correctCostateDirection ( StateEquationData data,
SplitDirection d 
)

Corrects the costate direction using the Jacobian of the Lie group.

Parameters
[in,out]dataData structure for the state equation.
[in,out]dSplit direction.

◆ correctLinearizeImpactStateEquation()

void robotoc::correctLinearizeImpactStateEquation ( const Robot robot,
const SplitSolution s,
const SplitSolution s_next,
StateEquationData data,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Corrects the linearized state equation using the Jacobian of the Lie group.

Parameters
[in]robotRobot model.
[in]sSolution at the current impact stage.
[in]s_nextSolution at the next time stage.
[in,out]dataData structure for the state equation.
[in,out]kkt_matrixImpact split KKT matrix at the current impact stage.
[in,out]kkt_residualImpact split KKT residual at the current impact stage.

◆ correctLinearizeStateEquation()

void robotoc::correctLinearizeStateEquation ( const Robot robot,
const double  dt,
const SplitSolution s,
const SplitSolution s_next,
StateEquationData data,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Corrects the linearized state equation using the Jacobian of the Lie group.

Parameters
[in]robotRobot model.
[in]dtTime step.
[in]sSolution at the current stage.
[in]s_nextSolution at the next time stage.
[in,out]dataData structure for the state equation.
[in,out]kkt_matrixSplit KKT matrix at the current time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ correctLinearizeTerminalStateEquation()

void robotoc::correctLinearizeTerminalStateEquation ( StateEquationData data,
SplitKKTMatrix kkt_matrix 
)

Corrects the linearized state equation using the Jacobian of the Lie group.

Parameters
[in,out]dataData structure for the state equation.
[in,out]kkt_matrixSplit KKT matrix at the current time stage.

◆ evalContactDynamics()

void robotoc::evalContactDynamics ( Robot robot,
const ContactStatus contact_status,
const SplitSolution s,
ContactDynamicsData data 
)

Computes the residual in the contact dynamics constraint.

Parameters
[in]robotRobot model.
[in]contact_statusContact status of this time stage.
[in]sSplit solution of this time stage.
[in,out]dataData structure for the contact dynamics.

◆ evalImpactDynamics()

void robotoc::evalImpactDynamics ( Robot robot,
const ImpactStatus impact_status,
const SplitSolution s,
ContactDynamicsData data 
)

Computes the residual in the impact dynamics constraint.

Parameters
[in]robotRobot model.
[in]impact_statusImpact status of this impact stage.
[in]sSplit solution of this impact stage.
[in,out]dataData structure for the contact dynamics.

◆ evalImpactStateEquation() [1/2]

void robotoc::evalImpactStateEquation ( const Robot robot,
const SplitSolution s,
const Eigen::VectorXd &  q_next,
const Eigen::VectorXd &  v_next,
SplitKKTResidual kkt_residual 
)

Computes the residual in the impact state equation.

Parameters
[in]robotRobot model.
[in]sSolution at the current impact stage.
[in]q_nextConfiguration at the next time stage.
[in]v_nextGeneralized velocity at the next time stage.
[in,out]kkt_residualImpact split KKT residual at the current impact stage.

◆ evalImpactStateEquation() [2/2]

void robotoc::evalImpactStateEquation ( const Robot robot,
const SplitSolution s,
const SplitSolution s_next,
SplitKKTResidual kkt_residual 
)

Computes the residual in the impact state equation.

Parameters
[in]robotRobot model.
[in]sSolution at the current impact stage.
[in]s_nextSolution at the next time stage.
[in,out]kkt_residualImpact split KKT residual at the current impact stage.

◆ evalStateEquation() [1/2]

void robotoc::evalStateEquation ( const Robot robot,
const double  dt,
const SplitSolution s,
const Eigen::VectorXd &  q_next,
const Eigen::VectorXd &  v_next,
SplitKKTResidual kkt_residual 
)

Computes the residual in the state equation.

Parameters
[in]robotRobot model.
[in]dtTime step.
[in]sSolution at the current time stage.
[in]q_nextConfiguration at the next time stage.
[in]v_nextGeneralized velocity at the next time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ evalStateEquation() [2/2]

void robotoc::evalStateEquation ( const Robot robot,
const double  dt,
const SplitSolution s,
const SplitSolution s_next,
SplitKKTResidual kkt_residual 
)

Computes the residual in the state equation.

Parameters
[in]robotRobot model.
[in]dtTime step.
[in]sSolution at the current time stage.
[in]s_nextSolution at the next time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ evalSwitchingConstraint()

void robotoc::evalSwitchingConstraint ( Robot robot,
const ImpactStatus impact_status,
SwitchingConstraintData data,
const double  dt1,
const double  dt2,
const SplitSolution s,
SplitKKTResidual kkt_residual 
)

Computes the residual in the switching constraint, i.e., the contact position constraint.

Note
The internal kinematics data of robot is updated.
Parameters
[in]robotRobot model. Kinematics must be updated.
[in]impact_statusImpact status.
[in,out]dataData structure for the switching constraint.
[in]dt1Time step of the time stage 2 stage before the impact.
[in]dt2Time step of the time stage just before the impact.
[in]sSplit solution of the time stage 2 stage before the impact.
[in,out]kkt_residualSplit KKT residual of the time stage 2 stage before the impact.

◆ evalUnconstrBackwardEuler()

void robotoc::evalUnconstrBackwardEuler ( const double  dt,
const Eigen::VectorXd &  q_prev,
const Eigen::VectorXd &  v_prev,
const SplitSolution s,
SplitKKTResidual kkt_residual 
)

Computes the residual in the state equation of backward Euler.

Parameters
[in]dtTime step.
[in]q_prevConfiguration at the previous time stage.
[in]v_prevGeneralized velocity at the previous time stage.
[in]sSolution at the current time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ evalUnconstrForwardEuler()

void robotoc::evalUnconstrForwardEuler ( const double  dt,
const SplitSolution s,
const SplitSolution s_next,
SplitKKTResidual kkt_residual 
)

Computes the residual in the state equation of forward Euler.

Parameters
[in]dtTime step.
[in]sSolution at the current time stage.
[in]s_nextSolution at the next time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ expandContactDynamicsDual()

void robotoc::expandContactDynamicsDual ( const double  dt,
const double  dts,
ContactDynamicsData data,
const SplitDirection d_next,
SplitDirection d 
)

Expands the dual variables, i.e., computes the Newton direction of the condensed dual variables (Lagrange multipliers) of this stage.

Parameters
[in]dtTime step of this time stage.
[in]dtsDirection of the switching time regarding of this time stage.
[in,out]dataData structure for the contact dynamics.
[in]d_nextSplit direction of the next stage.
[in,out]dSplit direction of this time stage.

◆ expandContactDynamicsPrimal()

void robotoc::expandContactDynamicsPrimal ( const ContactDynamicsData data,
SplitDirection d 
)

Expands the primal variables, i.e., computes the Newton direction of the condensed primal variables (acceleration a and the contact forces f) of this stage.

Parameters
[in]dataData structure for the contact dynamics.
[in,out]dSplit direction of this time stage.

◆ expandImpactDynamicsDual()

void robotoc::expandImpactDynamicsDual ( ContactDynamicsData data,
const SplitDirection d_next,
SplitDirection d 
)

Expands the dual variables, i.e., computes the Newton direction of the condensed dual variables (Lagrange multipliers) of this impact stage.

Parameters
[in,out]dataData structure for the contact dynamics.
[in]d_nextSplit direction of the next stage.
[in,out]dSplit direction of this impact stage.

◆ expandImpactDynamicsPrimal()

void robotoc::expandImpactDynamicsPrimal ( const ContactDynamicsData data,
SplitDirection d 
)

Expands the primal variables, i.e., computes the Newton direction of the condensed primal variables (impact change in the velocity dv and the impact forces f) of this impact stage.

Parameters
[in]dataData structure for the contact dynamics.
[in,out]dSplit direction of this impact stage.

◆ forwardRiccatiRecursion() [1/2]

void robotoc::forwardRiccatiRecursion ( const SplitKKTMatrix kkt_matrix,
const SplitKKTResidual kkt_residual,
const LQRPolicy lqr_policy,
SplitDirection d,
SplitDirection d_next,
const bool  sto,
const bool  has_next_sto_phase 
)

Performs the forward Riccati recursion and computes the state direction.

Parameters
[in]kkt_matrixSplit KKT matrix of this stage.
[in]kkt_residualSplit KKT residual of this stage.
[in]lqr_policyLQR policy of this stage.
[in]dSplit direction of this stage.
[in,out]d_nextSplit direction of the next stage.
[in]stoIf true, the STO sensitivities are also considered.
[in]has_next_sto_phaseFlag for wheather this phase has the next phase involving the STO problem.

◆ forwardRiccatiRecursion() [2/2]

void robotoc::forwardRiccatiRecursion ( const SplitKKTMatrix kkt_matrix,
const SplitKKTResidual kkt_residual,
const SplitDirection d,
SplitDirection d_next 
)

Performs the forward Riccati recursion and computes the state direction.

Parameters
[in]kkt_matrixSplit KKT matrix of this impact stage.
[in]kkt_residualSplit KKT residual of this impact stage.
[in]dSplit direction of this impact stage.
[in,out]d_nextSplit direction of the next stage.

◆ linearizeContactDynamics()

void robotoc::linearizeContactDynamics ( Robot robot,
const ContactStatus contact_status,
const SplitSolution s,
ContactDynamicsData data,
SplitKKTResidual kkt_residual 
)

Computes the residual and derivatives of the contact dynamics
constraint and derivatives of it.

Parameters
[in]robotRobot model.
[in]contact_statusContact status of this time stage.
[in]sSplit solution of this time stage.
[in,out]dataData structure for the contact dynamics.
[in,out]kkt_residualSplit KKT residual of this time stage.

◆ linearizeImpactDynamics()

void robotoc::linearizeImpactDynamics ( Robot robot,
const ImpactStatus impact_status,
const SplitSolution s,
ContactDynamicsData data,
SplitKKTResidual kkt_residual 
)

Linearizes the impact dynamics constraint.

Parameters
[in]robotRobot model.
[in]impact_statusImpact status of this impact stage.
[in]sSplit solution of this impact stage.
[in,out]dataData structure for the contact dynamics.
[in,out]kkt_residualSplit KKT residual of this impact stage.

◆ linearizeImpactStateEquation()

void robotoc::linearizeImpactStateEquation ( const Robot robot,
const Eigen::VectorXd &  q_prev,
const SplitSolution s,
const SplitSolution s_next,
StateEquationData data,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Linearizes the impact state equation.

Parameters
[in]robotRobot model.
[in]q_prevConfiguration at the previous time stage.
[in]sSolution at the current impact stage.
[in]s_nextSolution at the next time stage.
[in,out]dataData structure for the state equation.
[in,out]kkt_matrixImpact split KKT matrix at the current impact stage.
[in,out]kkt_residualImpact split KKT residual at the current impact stage.

◆ linearizeStateEquation()

void robotoc::linearizeStateEquation ( const Robot robot,
const double  dt,
const Eigen::VectorXd &  q_prev,
const SplitSolution s,
const SplitSolution s_next,
StateEquationData data,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Linearizes the state equation.

Parameters
[in]robotRobot model.
[in]dtTime step.
[in]q_prevConfiguration at the previous time stage.
[in]sSolution at the current stage.
[in]s_nextSolution at the next time stage.
[in,out]dataData structure for the state equation.
[in,out]kkt_matrixSplit KKT matrix at the current time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ linearizeSwitchingConstraint()

void robotoc::linearizeSwitchingConstraint ( Robot robot,
const ImpactStatus impact_status,
SwitchingConstraintData data,
const double  dt1,
const double  dt2,
const SplitSolution s,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Linearizes the switching constraint, i.e., the contact position constraint.

Note
The internal kinematics data of robot is updated.
Parameters
[in]robotRobot model. Kinematics must be updated.
[in]impact_statusImpact status.
[in,out]dataData structure for the switching constraint.
[in]dt1Time step of the time stage 2 stage before the impact.
[in]dt2Time step of the time stage just before the impact.
[in]sSplit solution of the time stage 2 stage before the impact.
[in,out]kkt_matrixSplit KKT matrix of the time stage 2 stage before the impact.
[in,out]kkt_residualSplit KKT residual of the time stage 2 stage before the impact.

◆ linearizeTerminalStateEquation()

void robotoc::linearizeTerminalStateEquation ( const Robot robot,
const Eigen::VectorXd &  q_prev,
const SplitSolution s,
StateEquationData data,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Linearizes the state equation at the teminal stage.

Parameters
[in]robotRobot model.
[in]q_prevConfiguration at the previous time stage.
[in]sSolution at the current stage.
[in,out]dataData structure for the state equation.
[in,out]kkt_matrixSplit KKT matrix at the current time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ linearizeUnconstrBackwardEuler()

void robotoc::linearizeUnconstrBackwardEuler ( const double  dt,
const Eigen::VectorXd &  q_prev,
const Eigen::VectorXd &  v_prev,
const SplitSolution s,
const SplitSolution s_next,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Linearizes the state equation of backward Euler.

Parameters
[in]dtTime step.
[in]q_prevConfiguration at the previous time stage.
[in]v_prevGeneralized velocity at the previous time stage.
[in]sSolution at the current tiem stage.
[in]s_nextSolution at the next time stage.
[in,out]kkt_matrixSplit KKT matrix at the current time stage.
[in,out]kkt_residualSplit KKT reisdual at the current time stage.

◆ linearizeUnconstrBackwardEulerTerminal()

void robotoc::linearizeUnconstrBackwardEulerTerminal ( const double  dt,
const Eigen::VectorXd &  q_prev,
const Eigen::VectorXd &  v_prev,
const SplitSolution s,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Linearizes the state equation of backward Euler at the terminal stage.

Parameters
[in]dtTime step.
[in]q_prevConfiguration at the previous time stage.
[in]v_prevGeneralized velocity at the previous time stage.
[in]sSolution at the current tiem stage.
[in,out]kkt_matrixSplit KKT matrix at the current time stage.
[in,out]kkt_residualSplit KKT reisdual at the current time stage.

◆ linearizeUnconstrForwardEuler()

void robotoc::linearizeUnconstrForwardEuler ( const double  dt,
const SplitSolution s,
const SplitSolution s_next,
SplitKKTMatrix kkt_matrix,
SplitKKTResidual kkt_residual 
)

Linearizes the state equation of forward Euler.

Parameters
[in]dtTime step.
[in]sSolution at the current stage.
[in]s_nextSolution at the next time stage.
[in,out]kkt_matrixSplit KKT matrix at the current time stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ linearizeUnconstrForwardEulerTerminal()

void robotoc::linearizeUnconstrForwardEulerTerminal ( const SplitSolution s,
SplitKKTResidual kkt_residual 
)

Linearizes the state equation of forward Euler.

Parameters
[in]sSolution at the current stage.
[in,out]kkt_residualSplit KKT residual at the current time stage.

◆ Log6Map()

template<typename SE3Type >
const Eigen::Matrix< double, 6, 1 > robotoc::Log6Map ( const SE3Type &  SE3_obj)

Applies Log6 map that transforms the SE3 into 6-dimensional vector.

Parameters
[in]SE3_objSE3 object
Returns
Transformed 6-dimensional vector.

◆ operator<<() [1/5]

std::ostream & robotoc::operator<< ( std::ostream &  os,
const Direction d 
)

◆ operator<<() [2/5]

std::ostream & robotoc::operator<< ( std::ostream &  os,
const KKTMatrix kkt_matrix 
)

◆ operator<<() [3/5]

std::ostream & robotoc::operator<< ( std::ostream &  os,
const KKTResidual kkt_residual 
)

◆ operator<<() [4/5]

std::ostream & robotoc::operator<< ( std::ostream &  os,
const RiccatiFactorization riccati 
)

◆ operator<<() [5/5]

std::ostream & robotoc::operator<< ( std::ostream &  os,
const Solution s 
)