Simulate a rigid body More...
Namespaces | |
pinocchio_robot | |
Classes | |
class | AnalyticalZMPCOGTrajectory |
class | Bsplines |
Bspline class. More... | |
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 | 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 : \begin{eqnarray*} {\bf x}_{k+1} & =& {\bf A} x_k + {\bf b} u_k \\ p_k &=& {\bf cx}_k\\ \end{eqnarray*} . More... | |
class | PatternGeneratorInterface |
This class is the interface between the Pattern Generator and the external world. More... | |
class | PinocchioRobot |
struct | PinocchioRobotFoot_t |
class | Polynome |
Class for computing trajectories. More... | |
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 |
Structure to store each foot position when the user is specifying a sequence of relative positions. More... | |
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 |
Structure to store each of the ZMP value, with a given direction at a certain time. More... | |
class | ZMPPreviewControlWithMultiBodyZMP |
Object to generate the angle positions every 5 ms from a set of absolute foot positions. More... | |
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 |
Dynamics matrices | |
typedef linear_dynamics_s | linear_dynamics_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) |
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 |
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 |
References PatternGeneratorJRL::CH_Point::col, and PatternGeneratorJRL::CH_Point::row.
Referenced by PatternGeneratorJRL::ComputeConvexHull::DoComputeConvexHull().
void PatternGeneratorJRL::DistanceCHRep | ( | CH_Point & | s1, |
CH_Point & | s2, | ||
double & | distance1, | ||
double & | distance2 | ||
) |
References PatternGeneratorJRL::CH_Point::col, and PatternGeneratorJRL::CH_Point::row.
Referenced by PatternGeneratorJRL::ComputeConvexHull::DoComputeConvexHull().
|
inline |
References i, PatternGeneratorJRL::COMPosition_s::pitch, PatternGeneratorJRL::COMPosition_s::roll, PatternGeneratorJRL::COMPosition_s::x, PatternGeneratorJRL::COMPosition_s::y, PatternGeneratorJRL::COMPosition_s::yaw, and PatternGeneratorJRL::COMPosition_s::z.
Referenced by PatternGeneratorJRL::IntermedQPMat::SupportState().
|
inline |
References PatternGeneratorJRL::RelativeFootPosition_s::sx.
|
inline |
|
inline |
References PatternGeneratorJRL::FootAbsolutePosition_t::ddomega, PatternGeneratorJRL::FootAbsolutePosition_t::ddomega2, PatternGeneratorJRL::FootAbsolutePosition_t::ddtheta, PatternGeneratorJRL::FootAbsolutePosition_t::ddx, PatternGeneratorJRL::FootAbsolutePosition_t::ddy, PatternGeneratorJRL::FootAbsolutePosition_t::ddz, PatternGeneratorJRL::FootAbsolutePosition_t::domega, PatternGeneratorJRL::FootAbsolutePosition_t::domega2, PatternGeneratorJRL::FootAbsolutePosition_t::dtheta, PatternGeneratorJRL::FootAbsolutePosition_t::dx, PatternGeneratorJRL::FootAbsolutePosition_t::dy, PatternGeneratorJRL::FootAbsolutePosition_t::dz, PatternGeneratorJRL::FootAbsolutePosition_t::omega, PatternGeneratorJRL::FootAbsolutePosition_t::omega2, PatternGeneratorJRL::FootAbsolutePosition_t::stepType, PatternGeneratorJRL::FootAbsolutePosition_t::theta, PatternGeneratorJRL::FootAbsolutePosition_t::time, PatternGeneratorJRL::FootAbsolutePosition_t::x, PatternGeneratorJRL::FootAbsolutePosition_t::y, and PatternGeneratorJRL::FootAbsolutePosition_t::z.
std::ostream& PatternGeneratorJRL::operator<< | ( | std::ostream & | o, |
const IntermedQPMat::objective_variant_s & | r | ||
) |
|
inline |
References PatternGeneratorJRL::HandAbsolutePosition_t::ddomega, PatternGeneratorJRL::HandAbsolutePosition_t::ddomega2, PatternGeneratorJRL::HandAbsolutePosition_t::ddtheta, PatternGeneratorJRL::HandAbsolutePosition_t::ddx, PatternGeneratorJRL::HandAbsolutePosition_t::ddy, PatternGeneratorJRL::HandAbsolutePosition_t::ddz, PatternGeneratorJRL::HandAbsolutePosition_t::domega, PatternGeneratorJRL::HandAbsolutePosition_t::domega2, PatternGeneratorJRL::HandAbsolutePosition_t::dtheta, PatternGeneratorJRL::HandAbsolutePosition_t::dx, PatternGeneratorJRL::HandAbsolutePosition_t::dy, PatternGeneratorJRL::HandAbsolutePosition_t::dz, PatternGeneratorJRL::HandAbsolutePosition_t::omega, PatternGeneratorJRL::HandAbsolutePosition_t::omega2, PatternGeneratorJRL::HandAbsolutePosition_t::stepType, PatternGeneratorJRL::HandAbsolutePosition_t::theta, PatternGeneratorJRL::HandAbsolutePosition_t::time, PatternGeneratorJRL::HandAbsolutePosition_t::x, PatternGeneratorJRL::HandAbsolutePosition_t::y, and PatternGeneratorJRL::HandAbsolutePosition_t::z.
|
inline |
|
inline |
|
inline |
std::ostream & PatternGeneratorJRL::operator<< | ( | ostream & | os, |
const AnalyticalZMPCOGTrajectory & | obj | ||
) |
References PatternGeneratorJRL::Polynome::GetCoefficients(), PatternGeneratorJRL::AnalyticalZMPCOGTrajectory::GetFromListOfCOGPolynomials(), PatternGeneratorJRL::AnalyticalZMPCOGTrajectory::GetFromListOfZMPPolynomials(), PatternGeneratorJRL::AnalyticalZMPCOGTrajectory::GetHyperbolicCoefficients(), PatternGeneratorJRL::AnalyticalZMPCOGTrajectory::GetNumberOfIntervals(), PatternGeneratorJRL::AnalyticalZMPCOGTrajectory::GetPolynomialDegrees(), i, and j.
WALK_GEN_JRL_EXPORT PatternGeneratorInterface* PatternGeneratorJRL::patternGeneratorInterfaceFactory | ( | PinocchioRobot * | ) |
Factory of Pattern generator interface.
Referenced by PatternGeneratorJRL::PatternGeneratorInterface::~PatternGeneratorInterface().
CH_Point PatternGeneratorJRL::HRP2CIO_GlobalP0 |