\doc Simulate a rigid body More...
Namespaces | |
pinocchio_robot | |
Classes | |
class | AnalyticalZMPCOGTrajectory |
class | Bsplines |
class | BSplinesFoot |
Bsplines used for Z trajectory of stair steps. More... | |
struct | CH_Point |
struct | Circle_t |
Structure to model a circle (e.g : a stricly convex obstable) More... | |
struct | COMPosition_s |
Structure to store the COM position computed by the preview control. More... | |
class | ComputeConvexHull |
struct | COMState_s |
Structure to store the COM state computed by the preview control. More... | |
struct | ControlLoopOneStepArgs |
struct | FootAbsolutePosition_t |
Structure to store the absolute foot position. More... | |
class | FootConstraintsAsLinearSystem |
class | FootHalfSize |
struct | HandAbsolutePosition_t |
Structure to store the absolute foot position. More... | |
class | IntermedQPMat |
Custom (value based) container providing intermediate elements for the construction of a QP. More... | |
struct | linear_dynamics_s |
struct | LinearConstraintInequality_s |
struct | LinearConstraintInequalityFreeFeet_s |
Linear constraints with variable feet placement. More... | |
class | LinearizedInvertedPendulum2D |
struct | ltCH_Point |
class | OptimalControllerSolver |
This class computes the gains for preview control for a given discrete system. The discrete system is defined by three matrix A, b, c such as : More... | |
class | PatternGeneratorInterface |
class | PinocchioRobot |
struct | PinocchioRobotFoot_t |
class | Polynome |
class | Polynome3 |
Polynome used for X,Y and Theta trajectories. More... | |
class | Polynome4 |
Polynome used for Z trajectory. More... | |
class | Polynome5 |
Polynome used for X,Y and Theta trajectories. More... | |
class | Polynome6 |
Polynome used for Z trajectory. More... | |
class | Polynome7 |
Polynome used for X,Y and Theta trajectories. More... | |
class | PolynomeFoot |
class | PreviewControl |
Class to implement the preview control. More... | |
struct | ReferenceAbsoluteVelocity_t |
Structure to store the absolute reference. More... | |
class | RelativeFeetInequalities |
Generate a stack of inequalities relative to feet centers for the whole preview window. More... | |
struct | RelativeFootPosition_s |
struct | rigid_body_state_s |
State vectors. More... | |
class | RigidBody |
class | RigidBodySystem |
class | StepOverClampedCubicSpline |
class | StepOverPolynomeFoot |
Polynome used for Z trajectory during stepover. More... | |
class | StepOverPolynomeFootXtoTime |
Polynome used for X trajectory in function of time to combine with StepOverPolynomeFootZtoX. More... | |
class | StepOverPolynomeFootZtoX |
Polynome used for Z trajectory during stepover. More... | |
class | StepOverPolynomeHip4 |
Polynome for the hip trajectory. More... | |
class | StepOverSpline |
spline function calculation class to calculate cubic splines More... | |
struct | SupportFeet_s |
class | SupportFSM |
Finite state machine to determine the support parameters. More... | |
struct | ZMPPosition_s |
class | ZMPPreviewControlWithMultiBodyZMP |
Typedefs | |
typedef struct COMPosition_s | COMPosition |
typedef struct COMPosition_s | WaistState |
typedef struct COMState_s | COMState |
typedef struct RelativeFootPosition_s | RelativeFootPosition |
typedef struct ZMPPosition_s | ZMPPosition |
typedef struct FootAbsolutePosition_t | FootAbsolutePosition |
typedef struct HandAbsolutePosition_t | HandAbsolutePosition |
typedef struct LinearConstraintInequality_s | LinearConstraintInequality_t |
typedef struct LinearConstraintInequalityFreeFeet_s | LinearConstraintInequalityFreeFeet_t |
typedef struct SupportFeet_s | SupportFeet_t |
typedef struct ReferenceAbsoluteVelocity_t | ReferenceAbsoluteVelocity |
typedef struct Circle_t | Circle |
typedef PinocchioRobotFoot_t | PRFoot |
typedef std::vector< CH_Point > | ConvexHullList |
typedef struct rigid_body_state_s | rigid_body_state_t |
Functions | |
WALK_GEN_JRL_EXPORT PatternGeneratorInterface * | patternGeneratorInterfaceFactory (PinocchioRobot *) |
std::ostream & | operator<< (std::ostream &os, const COMPosition_s &aCp) |
std::ostream & | operator<< (std::ostream &os, const RelativeFootPosition_s &rfp) |
std::ostream & | operator<< (std::ostream &os, const ZMPPosition_s &zmp) |
std::ostream & | operator<< (std::ostream &os, const FootAbsolutePosition &fap) |
std::ostream & | operator<< (std::ostream &os, const HandAbsolutePosition &hap) |
std::ostream & | operator<< (std::ostream &os, const SupportFeet_s &sf) |
std::ostream & | operator<< (std::ostream &os, const ReferenceAbsoluteVelocity_t &rav) |
std::ostream & | operator<< (std::ostream &os, const Circle_t &circle) |
ostream & | operator<< (ostream &os, const AnalyticalZMPCOGTrajectory &obj) |
std::ostream & | operator<< (std::ostream &os, const AnalyticalZMPCOGTrajectory &obj) |
void | DistanceCHRep (CH_Point &s1, CH_Point &s2, double &distance1, double &distance2) |
double | CompareCBRep (CH_Point &s1, CH_Point &s2) |
std::ostream & | operator<< (std::ostream &o, const IntermedQPMat::objective_variant_s &r) |
Variables | |
CH_Point | HRP2CIO_GlobalP0 |
\doc Simulate a rigid body
STL includes
Framework includes
typedef struct Circle_t PatternGeneratorJRL::Circle |
typedef struct COMPosition_s PatternGeneratorJRL::COMPosition |
typedef struct COMState_s PatternGeneratorJRL::COMState |
typedef std::vector<CH_Point> PatternGeneratorJRL::ConvexHullList |
typedef struct FootAbsolutePosition_t PatternGeneratorJRL::FootAbsolutePosition |
typedef struct HandAbsolutePosition_t PatternGeneratorJRL::HandAbsolutePosition |
typedef struct LinearConstraintInequalityFreeFeet_s PatternGeneratorJRL::LinearConstraintInequalityFreeFeet_t |
typedef struct RelativeFootPosition_s PatternGeneratorJRL::RelativeFootPosition |
typedef struct rigid_body_state_s PatternGeneratorJRL::rigid_body_state_t |
typedef struct SupportFeet_s PatternGeneratorJRL::SupportFeet_t |
typedef struct COMPosition_s PatternGeneratorJRL::WaistState |
typedef struct ZMPPosition_s PatternGeneratorJRL::ZMPPosition |
void PatternGeneratorJRL::DistanceCHRep | ( | CH_Point & | s1, |
CH_Point & | s2, | ||
double & | distance1, | ||
double & | distance2 | ||
) |
ostream& PatternGeneratorJRL::operator<< | ( | ostream & | os, |
const AnalyticalZMPCOGTrajectory & | obj | ||
) |
std::ostream& PatternGeneratorJRL::operator<< | ( | std::ostream & | o, |
const IntermedQPMat::objective_variant_s & | r | ||
) |
std::ostream& PatternGeneratorJRL::operator<< | ( | std::ostream & | os, |
const AnalyticalZMPCOGTrajectory & | obj | ||
) |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
WALK_GEN_JRL_EXPORT PatternGeneratorInterface* PatternGeneratorJRL::patternGeneratorInterfaceFactory | ( | PinocchioRobot * | ) |
Factory of Pattern generator interface.
CH_Point PatternGeneratorJRL::HRP2CIO_GlobalP0 |