This class provides dynamically stable CoM, ZMP, feet trajectories. It wraps up the algorithms implemented by the walkGenJRL library. More...
#include <sot/pattern-generator/pg.h>


Public Types | |
| typedef int | Dummy |
Public Member Functions | |
| DYNAMIC_GRAPH_ENTITY_DECL () | |
| PatternGenerator (const std::string &name="PatternGenerator") | |
| Default constructor. | |
| virtual | ~PatternGenerator (void) |
| Default destructor. | |
| void | initCommands (void) |
| int | stringToReferenceEnum (const std::string &FrameReference) |
| void | setReferenceFromString (const std::string &str) |
| void | addOnLineStep (const double &x, const double &y, const double &th) |
| void | addStep (const double &x, const double &y, const double &th) |
| void | pgCommandLine (const std::string &cmdline) |
| void | useFeedBackSignals (const bool &feedBack) |
| void | useDynamicFilter (const bool &dynamicFilter) |
| void | debug (void) |
Methods related to the data files. | |
| bool | buildPGI (void) |
| Build the pattern generator interface from the parameter "/robot_description" and the informations in "/robot/specifificities/feet/[right|left]/[size|anklePosition]. | |
| bool | addComplementaryFrames () |
| Add complementary frame. | |
| bool | buildReducedModel (void) |
| Build the reduced model. | |
| void | readFootParameters (std::string &rootFootPath, pg::PRFoot &aFoot) |
| readFootParameters | |
| bool | InitState (void) |
| Initialize the state of the robot. | |
| void | setPreviewControlParametersFile (const std::string &filename) |
| Set the directory which contains the parameters for the preview control. | |
| void | setURDFFile (const std::string &filename) |
| Set the path which contains the URDF files robot's model. | |
| void | setSRDFFile (const std::string &filename) |
| Set the path which contains the SRDF files robot's model. More precisely this file describes which joints are the hands, feet. For more information please see the documentation of walkGenJRL. | |
| void | setXmlRankFile (const std::string &filename) |
| Set the path which contains the Joint Rank model. | |
| void | setParamPreviewFile (const std::string &filename) |
| Set the name of the file specifying the control parameters of the preview control. | |
| void | setSoleParameters (const double &inSoleLength, const double &inSoleWidth) |
| Set the foot parameters. | |
| void | addJointMapping (const std::string &link, const std::string &repName) |
| Set mapping between a link and actual robot name. | |
| pg::PatternGeneratorInterface * | GetPatternGeneratorInterface () |
| Give access directly to the pattern generator... You really have to know what your are doing. | |
Public Attributes | |
| SignalTimeDependent< int, int > | contactPhaseSOUT |
| Int Vector of support phase: leftFoot=1, rightFoot=-1, doubleSupport=0 (see enum). | |
Internal signals. | |
| SignalTimeDependent< Dummy, int > | firstSINTERN |
| Internal signal for initialization and one shot signals. | |
| SignalTimeDependent< Dummy, int > | OneStepOfControlS |
| Internal signal to trigger one step of the algorithm. | |
External signals | |
| SignalPtr< dynamicgraph::Vector, int > | jointPositionSIN |
| Real state position values. | |
| SignalPtr< dynamicgraph::Vector, int > | motorControlJointPositionSIN |
| Motor control joint position values. | |
| SignalPtr< dynamicgraph::Vector, int > | ZMPPreviousControllerSIN |
| Previous ZMP value (ZMP send by the preceding controller). | |
| SignalTimeDependent< dynamicgraph::Vector, int > | ZMPRefSOUT |
| Externalize the ZMP reference . | |
| SignalTimeDependent< dynamicgraph::Vector, int > | CoMRefSOUT |
| Externalize the CoM reference. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | dCoMRefSOUT |
| Externalize the CoM reference. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | ddCoMRefSOUT |
| SignalPtr< dynamicgraph::Vector, int > | comSIN |
| Take the current CoM. | |
| SignalPtr< dynamicgraph::Vector, int > | comStateSIN |
| Take the current CoM state (pos, vel, acc). | |
| SignalPtr< dynamicgraph::Vector, int > | zmpSIN |
| Take the current zmp (x, y, z). | |
| SignalPtr< dynamicgraph::Vector, int > | forceSIN |
| Take the current external force applied to the com (fx, fy, fz). | |
| SignalTimeDependent< dynamicgraph::Vector, int > | forceSOUT |
| dynamicgraph::Vector | m_initForce |
| dynamicgraph::Vector | m_currentForces |
| std::deque< dynamicgraph::Vector > | m_bufferForce |
| std::vector< double > | m_filterWindow |
| SignalPtr< dynamicgraph::Vector, int > | velocitydesSIN |
| Take the current desired velocity. | |
| SignalPtr< bool, int > | triggerSIN |
| Take the current trigger to start OneStepOfControl. | |
| SignalPtr< MatrixHomogeneous, int > | LeftFootCurrentPosSIN |
| Take the current left foot homogeneous position. | |
| SignalPtr< MatrixHomogeneous, int > | RightFootCurrentPosSIN |
| Take the current right foot homogeneous position. | |
| SignalTimeDependent< MatrixHomogeneous, int > | LeftFootRefSOUT |
| Externalize the left foot position reference. | |
| SignalTimeDependent< MatrixHomogeneous, int > | RightFootRefSOUT |
| Externalize the right foot position reference. | |
| SignalTimeDependent< MatrixHomogeneous, int > | dotLeftFootRefSOUT |
| Externalize the left foot position reference. | |
| SignalTimeDependent< MatrixHomogeneous, int > | dotRightFootRefSOUT |
| Externalize the right foot position reference. | |
| SignalTimeDependent< MatrixHomogeneous, int > | FlyingFootRefSOUT |
| Externalize the foot which is not considered as support foot, the information are given in a relative referentiel. | |
| SignalTimeDependent< int, int > | SupportFootSOUT |
| Externalize the support foot. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | jointWalkingErrorPositionSOUT |
| Externalize the joint values for walking. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | comattitudeSOUT |
| Externalize the com attitude. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | dcomattitudeSOUT |
| Externalize the dcom attitude. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | ddcomattitudeSOUT |
| Externalize the ddcom attitude. | |
| SignalTimeDependent< VectorRollPitchYaw, int > | waistattitudeSOUT |
| Externalize the waist attitude. | |
| SignalTimeDependent< VectorRollPitchYaw, int > | waistattitudeabsoluteSOUT |
| Externalize the absolute waist attitude. | |
| SignalTimeDependent< MatrixHomogeneous, int > | waistattitudematrixabsoluteSOUT |
| Externalize the absolute waist attitude into a homogeneous matrix. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | waistpositionSOUT |
| Externalize the waist position. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | waistpositionabsoluteSOUT |
| Externalize the absolute waist position. | |
| SignalTimeDependent< unsigned int, int > | dataInProcessSOUT |
| true iff PG is processing. Use it for synchronize. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | InitZMPRefSOUT |
| Externalize the initial ZMP reference . | |
| SignalTimeDependent< dynamicgraph::Vector, int > | InitCoMRefSOUT |
| Externalize the initial CoM reference. | |
| SignalTimeDependent< dynamicgraph::Vector, int > | InitWaistPosRefSOUT |
| Externalize the initial Waist reference. | |
| SignalTimeDependent< VectorRollPitchYaw, int > | InitWaistAttRefSOUT |
| Externalize the initial Waist reference. | |
| SignalTimeDependent< MatrixHomogeneous, int > | InitLeftFootRefSOUT |
| Externalize the left foot position reference. | |
| SignalTimeDependent< MatrixHomogeneous, int > | InitRightFootRefSOUT |
| Externalize the right foot position reference. | |
| SignalTimeDependent< bool, int > | leftFootContactSOUT |
| Booleans for contact of the feet. | |
| SignalTimeDependent< bool, int > | rightFootContactSOUT |
Static Public Attributes | |
Some constant to define the type | |
of frame reference. | |
| static const int | WORLD_FRAME = 0 |
| Specify that the frame is expressed in the world reference frame. | |
| static const int | EGOCENTERED_FRAME = 1 |
| Specify that the frame is expressed in the robot ego centered frame. | |
| static const int | LEFT_FOOT_CENTERED_FRAME = 2 |
| Specify that the frame is expressed in the left foot centered frame. | |
| static const int | WAIST_CENTERED_FRAME = 3 |
| Specify that the frame is expressed in the waist centered frame. | |
Protected Member Functions | |
| int & | getSupportFoot (int &res, int time) |
| Getting the current support foot: 1 Left -1 Right. | |
| int & | InitOneStepOfControl (int &dummy, int time) |
| Trigger the initialization of the algorithm. | |
| int & | OneStepOfControl (int &dummy, int time) |
| Trigger one step of the algorithm. | |
| void | ParseCmdFile (std::istringstream &cmdArg, std::ostream &os) |
| void | FromAbsoluteFootPosToDotHomogeneous (pg::FootAbsolutePosition aFootPosition, MatrixHomogeneous &aFootMH, MatrixHomogeneous &adotFootMH) |
| Transfert from a current absolute foot position to a dot homogeneous matrix. | |
| void | FromAbsoluteFootPosToHomogeneous (pg::FootAbsolutePosition aFootPosition, MatrixHomogeneous &aFootMH) |
| Transfert from a current absolute foot position to a homogeneous matrix. | |
| void | getAbsoluteWaistPosAttHomogeneousMatrix (MatrixHomogeneous &aWaistMH) |
| Provide an homogeneous matrix from the current waist position and attitude. | |
| void | SubsamplingFootPos (pg::FootAbsolutePosition &PrevFootPosition, pg::FootAbsolutePosition &NextFootPosition, MatrixHomogeneous &FootPositionOut, MatrixHomogeneous &dotFootPositionOut, unsigned int &count) |
| void | SubsamplingVector (dynamicgraph::Vector &PrevPosition, dynamicgraph::Vector &NextPosition, dynamicgraph::Vector &PositionOut, unsigned int &count) |
| void | CopyFootPosition (pg::FootAbsolutePosition &FootPositionIn, pg::FootAbsolutePosition &FootPositionOut) |
| dynamicgraph::Vector & | getInitZMPRef (dynamicgraph::Vector &res, int time) |
| Internal method to get the initial reference ZMP at a given time. | |
| dynamicgraph::Vector & | getInitCoMRef (dynamicgraph::Vector &res, int time) |
| Internal method to get the initial reference CoM at a given time. | |
| dynamicgraph::Vector & | getInitWaistPosRef (dynamicgraph::Vector &res, int time) |
| Internal method to get the initial reference CoM at a given time. | |
| VectorRollPitchYaw & | getInitWaistAttRef (VectorRollPitchYaw &res, int time) |
| Internal method to get the initial reference CoM at a given time. | |
| MatrixHomogeneous & | getInitLeftFootRef (MatrixHomogeneous &res, int time) |
| Internal method to get the position of the left foot. | |
| MatrixHomogeneous & | getInitRightFootRef (MatrixHomogeneous &res, int time) |
| Internal method to get the position of the right foot. | |
| bool & | getLeftFootContact (bool &res, int time) |
| Internal method to get the information of contact or not on the feet. | |
| bool & | getRightFootContact (bool &res, int time) |
| int & | getContactPhase (int &res, int time) |
| Internal method to get the information of contact phase leftFoot=1, rightFoot=-1, doubleSupport=0. | |
Internal methods to access reference trajectories. | |
| dynamicgraph::Vector & | getZMPRef (dynamicgraph::Vector &res, int time) |
| Internal method to get the reference ZMP at a given time. | |
| dynamicgraph::Vector & | getCoMRef (dynamicgraph::Vector &res, int time) |
| Internal method to get the reference CoM at a given time. | |
| dynamicgraph::Vector & | getdCoMRef (dynamicgraph::Vector &res, int time) |
| Internal method to get the reference dCoM at a given time. | |
| dynamicgraph::Vector & | getddCoMRef (dynamicgraph::Vector &res, int time) |
| Internal method to get the reference ddCoM at a given time. | |
| dynamicgraph::Vector & | getExternalForces (dynamicgraph::Vector &forces, int time) |
| Internal method to get the external forces at a given time. | |
| MatrixHomogeneous & | getLeftFootRef (MatrixHomogeneous &res, int time) |
| Internal method to get the position of the left foot. | |
| MatrixHomogeneous & | getRightFootRef (MatrixHomogeneous &res, int time) |
| Internal method to get the position of the right foot. | |
| MatrixHomogeneous & | getdotLeftFootRef (MatrixHomogeneous &res, int time) |
| Internal method to get the derivative of the left foot. | |
| MatrixHomogeneous & | getdotRightFootRef (MatrixHomogeneous &res, int time) |
| Internal method to get the derivative of the right foot. | |
| MatrixHomogeneous & | getFlyingFootRef (MatrixHomogeneous &res, int time) |
| Internal method to get the position of the flying foot. | |
| dynamicgraph::Vector & | getjointWalkingErrorPosition (dynamicgraph::Vector &res, int time) |
| Internal method to get the joint position for walking. | |
| dynamicgraph::Vector & | getdComAttitude (dynamicgraph::Vector &res, int time) |
| Internal method to get the derivative of the com attitude. | |
| dynamicgraph::Vector & | getddComAttitude (dynamicgraph::Vector &res, int time) |
| Internal method to get the second derivative of the com attitude. | |
| dynamicgraph::Vector & | getComAttitude (dynamicgraph::Vector &res, int time) |
| Internal method to get the attitude of the com. | |
| VectorRollPitchYaw & | getWaistAttitude (VectorRollPitchYaw &res, int time) |
| Internal method to get the attitude of the waist. | |
| VectorRollPitchYaw & | getWaistAttitudeAbsolute (VectorRollPitchYaw &res, int time) |
| Internal method to get the absolute attitude of the waist. | |
| MatrixHomogeneous & | getWaistAttitudeMatrixAbsolute (MatrixHomogeneous &res, int time) |
| Internal method to get the absolute attitude of the waist into an homogeneous matrix. | |
| unsigned & | getDataInProcess (unsigned &res, int time) |
| Internal method to get the dataInPorcess flag. | |
| dynamicgraph::Vector & | getWaistPosition (dynamicgraph::Vector &res, int time) |
| Internal method to get the position of the waist. | |
| dynamicgraph::Vector & | getWaistPositionAbsolute (dynamicgraph::Vector &res, int time) |
| Internal method to get the absolute position of the waist. | |
Protected Attributes | |
| pinocchio::Model | m_robotModel |
| The model of the robot. | |
| pg::PinocchioRobot * | m_PR |
| Pointer towards the robot model inside jrl-walkgen. | |
| pinocchio::Data * | m_robotData |
| The pointor toward the robot data. | |
| pg::PatternGeneratorInterface * | m_PGI |
| Pointer towards the interface of the pattern generator. | |
| bool | m_init |
| Boolean variable to initialize the object by loading an object. | |
| bool | m_InitPositionByRealState |
| Boolean variable to initialize the position: first through the real state of the robot, then through the motor command. | |
| int | m_SupportFoot |
| Integer for the support foot. | |
| int | m_ReferenceFrame |
| Keep the frame reference. | |
| double | m_AnkleSoilDistance |
| Distance between ankle and soil. | |
| double | m_TimeStep |
| Time step. | |
| SupportPhase | m_ContactPhase |
| Current support/contact phase defined by enum: leftFoot=1, rightFoot=-1, doubleSupport=0. | |
| int | m_DSStartingTime |
| int | m_LocalTime |
| iteration time. | |
| unsigned int | m_count |
| count for subsampling. | |
| std::string | m_left_ankle_body_name |
| std::string | m_right_ankle_body_name |
| std::string | m_left_wrist_body_name |
| std::string | m_right_wrist_body_name |
| Eigen::VectorXd | m_ZMPPrevious |
Fields to store name and positions of data files | |
| std::string | m_PreviewControlParametersFile |
| Some information related to the preview control. | |
| std::string | m_urdfFile |
| Directory+Name where the URDF file of the robot's model is located. | |
| std::string | m_srdfFile |
| Directory+Name where the SRDF file of the robot's model is located. | |
| std::string | m_xmlRankFile |
| Directory+Name where the Rank of the joints are notified. | |
| std::vector< unsigned > | m_wrml2urdfIndex |
| double | m_soleLength |
| Lenght of the sole. | |
| double | m_soleWidth |
| Width of the sole. | |
| std::map< std::string, std::string > | specialJoints_ |
Keep information computed once for each time. | |
| MatrixHomogeneous | m_k_Waist_kp1 |
| Rigit motion between two waist positions at the beginning of the walking and at the end of the walking. | |
| MatrixHomogeneous | m_LeftFootPosition |
| Absolute Position for the left and right feet. | |
| MatrixHomogeneous | m_RightFootPosition |
| PatternGeneratorJRL::FootAbsolutePosition | m_PrevSamplingRightFootAbsPos |
| PatternGeneratorJRL::FootAbsolutePosition | m_PrevSamplingLeftFootAbsPos |
| PatternGeneratorJRL::FootAbsolutePosition | m_NextSamplingRightFootAbsPos |
| PatternGeneratorJRL::FootAbsolutePosition | m_NextSamplingLeftFootAbsPos |
| PatternGeneratorJRL::FootAbsolutePosition | m_InitRightFootAbsPos |
| PatternGeneratorJRL::FootAbsolutePosition | m_InitLeftFootAbsPos |
| MatrixHomogeneous | m_dotLeftFootPosition |
| Absolute Derivate for the left and right feet. | |
| MatrixHomogeneous | m_dotRightFootPosition |
| MatrixHomogeneous | m_InitLeftFootPosition |
| Initial Absolute Starting Position for the left and right feet. | |
| MatrixHomogeneous | m_InitRightFootPosition |
| MatrixHomogeneous | m_MotionSinceInstanciationToThisSequence |
| Keep track of the motion between sequence of motions. | |
| MatrixHomogeneous | m_FlyingFootPosition |
| Relative Position of the flying foot. | |
| dynamicgraph::Vector | m_ZMPRefPos |
| Absolute position of the reference ZMP. | |
| dynamicgraph::Vector | m_ComAttitude |
| Com Attitude: does not really exist apart from when the robot is seen as an inverted pendulum. | |
| dynamicgraph::Vector | m_dComAttitude |
| dCom Attitude: does not really exist apart when the robot is seen as an inverted pendulum | |
| dynamicgraph::Vector | m_ddComAttitude |
| ddCom Attitude: does not really exist apart when the robot is seen as an inverted pendulum | |
| dynamicgraph::Vector | m_COMRefPos |
| Absolute position of the reference CoM. | |
| dynamicgraph::Vector | m_PrevSamplingCOMRefPos |
| dynamicgraph::Vector | m_NextSamplingCOMRefPos |
| dynamicgraph::Vector | m_dCOMRefPos |
| Absolute position of the reference dCoM. | |
| dynamicgraph::Vector | m_PrevSamplingdCOMRefPos |
| dynamicgraph::Vector | m_NextSamplingdCOMRefPos |
| dynamicgraph::Vector | m_ddCOMRefPos |
| Absolute position of the reference ddCoM. | |
| dynamicgraph::Vector | m_PrevSamplingddCOMRefPos |
| dynamicgraph::Vector | m_NextSamplingddCOMRefPos |
| dynamicgraph::Vector | m_InitZMPRefPos |
| Initial Absolute position of the reference ZMP. | |
| dynamicgraph::Vector | m_InitWaistRefPos |
| Initial Absolute position and attitude of the reference Waist. | |
| dynamicgraph::Vector | m_InitWaistRefAtt |
| dynamicgraph::Vector | m_InitCOMRefPos |
| Initial Absolute position of the reference CoM. | |
| dynamicgraph::Vector | m_WaistPosition |
| Waist position. | |
| dynamicgraph::Vector | m_WaistPositionAbsolute |
| Waist position Absolute. | |
| dynamicgraph::Vector | m_WaistAttitude |
| Waist Attitude. | |
| dynamicgraph::Vector | m_WaistAttitudeAbsolute |
| Waist Attitude Absolute. | |
| dynamicgraph::Vector | m_PrevSamplingWaistAttAbs |
| dynamicgraph::Vector | m_NextSamplingWaistAttAbs |
| MatrixHomogeneous | m_WaistAttitudeMatrixAbsolute |
| Waist Attitude Homogeneous Matrix. | |
| dynamicgraph::Vector | m_JointErrorValuesForWalking |
| Joint values for walking. | |
| dynamicgraph::Vector | m_VelocityReference |
| Velocity reference for Herdt's PG. | |
| bool | m_trigger |
| trigger to start walking | |
| unsigned int | m_dataInProcess |
| true iff the pattern if dealing with data, false if pg is not working anymore/yet. | |
| bool | m_feedBackControl |
| Booleans used to indicate if feedback signals shoul be used or not. | |
| bool | m_forceFeedBack |
| Booleans used to indicate if force feedback signals shoul be used or not. | |
| bool | m_rightFootContact |
| Booleans used to indicate feet contacts. | |
| bool | m_leftFootContact |
This class provides dynamically stable CoM, ZMP, feet trajectories. It wraps up the algorithms implemented by the walkGenJRL library.
| typedef int dynamicgraph::sot::PatternGenerator::Dummy |
| dynamicgraph::sot::PatternGenerator::PatternGenerator | ( | const std::string & | name = "PatternGenerator" | ) |
Default constructor.
|
virtual |
Default destructor.
| bool dynamicgraph::sot::PatternGenerator::addComplementaryFrames | ( | ) |
Add complementary frame.
| void dynamicgraph::sot::PatternGenerator::addJointMapping | ( | const std::string & | link, |
| const std::string & | repName | ||
| ) |
Set mapping between a link and actual robot name.
| void dynamicgraph::sot::PatternGenerator::addOnLineStep | ( | const double & | x, |
| const double & | y, | ||
| const double & | th | ||
| ) |
| void dynamicgraph::sot::PatternGenerator::addStep | ( | const double & | x, |
| const double & | y, | ||
| const double & | th | ||
| ) |
| bool dynamicgraph::sot::PatternGenerator::buildPGI | ( | void | ) |
Build the pattern generator interface from the parameter "/robot_description" and the informations in "/robot/specifificities/feet/[right|left]/[size|anklePosition].
| bool dynamicgraph::sot::PatternGenerator::buildReducedModel | ( | void | ) |
Build the reduced model.
|
protected |
| void dynamicgraph::sot::PatternGenerator::debug | ( | void | ) |
| dynamicgraph::sot::PatternGenerator::DYNAMIC_GRAPH_ENTITY_DECL | ( | ) |
Class name
|
protected |
Transfert from a current absolute foot position to a dot homogeneous matrix.
|
protected |
Transfert from a current absolute foot position to a homogeneous matrix.
|
protected |
Provide an homogeneous matrix from the current waist position and attitude.
|
protected |
Internal method to get the attitude of the com.
|
protected |
Internal method to get the reference CoM at a given time.
|
protected |
Internal method to get the information of contact phase leftFoot=1, rightFoot=-1, doubleSupport=0.
|
protected |
Internal method to get the dataInPorcess flag.
|
protected |
Internal method to get the derivative of the com attitude.
|
protected |
Internal method to get the reference dCoM at a given time.
|
protected |
Internal method to get the second derivative of the com attitude.
|
protected |
Internal method to get the reference ddCoM at a given time.
|
protected |
Internal method to get the derivative of the left foot.
|
protected |
Internal method to get the derivative of the right foot.
|
protected |
Internal method to get the external forces at a given time.
|
protected |
Internal method to get the position of the flying foot.
|
protected |
Internal method to get the initial reference CoM at a given time.
|
protected |
Internal method to get the position of the left foot.
|
protected |
Internal method to get the position of the right foot.
|
protected |
Internal method to get the initial reference CoM at a given time.
|
protected |
Internal method to get the initial reference CoM at a given time.
|
protected |
Internal method to get the initial reference ZMP at a given time.
|
protected |
Internal method to get the joint position for walking.
|
protected |
Internal method to get the information of contact or not on the feet.
|
protected |
Internal method to get the position of the left foot.
|
inline |
Give access directly to the pattern generator... You really have to know what your are doing.
|
protected |
|
protected |
Internal method to get the position of the right foot.
|
protected |
Getting the current support foot: 1 Left -1 Right.
|
protected |
Internal method to get the attitude of the waist.
|
protected |
Internal method to get the absolute attitude of the waist.
|
protected |
Internal method to get the absolute attitude of the waist into an homogeneous matrix.
|
protected |
Internal method to get the position of the waist.
|
protected |
Internal method to get the absolute position of the waist.
|
protected |
Internal method to get the reference ZMP at a given time.
| void dynamicgraph::sot::PatternGenerator::initCommands | ( | void | ) |
|
protected |
Trigger the initialization of the algorithm.
| bool dynamicgraph::sot::PatternGenerator::InitState | ( | void | ) |
Initialize the state of the robot.
|
protected |
Trigger one step of the algorithm.
|
protected |
Parsing a file of command by the walking pattern generator interface.
| void dynamicgraph::sot::PatternGenerator::pgCommandLine | ( | const std::string & | cmdline | ) |
| void dynamicgraph::sot::PatternGenerator::readFootParameters | ( | std::string & | rootFootPath, |
| pg::PRFoot & | aFoot | ||
| ) |
readFootParameters
| void dynamicgraph::sot::PatternGenerator::setParamPreviewFile | ( | const std::string & | filename | ) |
Set the name of the file specifying the control parameters of the preview control.
| void dynamicgraph::sot::PatternGenerator::setPreviewControlParametersFile | ( | const std::string & | filename | ) |
Set the directory which contains the parameters for the preview control.
| void dynamicgraph::sot::PatternGenerator::setReferenceFromString | ( | const std::string & | str | ) |
| void dynamicgraph::sot::PatternGenerator::setSoleParameters | ( | const double & | inSoleLength, |
| const double & | inSoleWidth | ||
| ) |
Set the foot parameters.
| void dynamicgraph::sot::PatternGenerator::setSRDFFile | ( | const std::string & | filename | ) |
Set the path which contains the SRDF files robot's model. More precisely this file describes which joints are the hands, feet. For more information please see the documentation of walkGenJRL.
| void dynamicgraph::sot::PatternGenerator::setURDFFile | ( | const std::string & | filename | ) |
Set the path which contains the URDF files robot's model.
| void dynamicgraph::sot::PatternGenerator::setXmlRankFile | ( | const std::string & | filename | ) |
Set the path which contains the Joint Rank model.
| int dynamicgraph::sot::PatternGenerator::stringToReferenceEnum | ( | const std::string & | FrameReference | ) |
|
protected |
|
protected |
| void dynamicgraph::sot::PatternGenerator::useDynamicFilter | ( | const bool & | dynamicFilter | ) |
| void dynamicgraph::sot::PatternGenerator::useFeedBackSignals | ( | const bool & | feedBack | ) |
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::comattitudeSOUT |
Externalize the com attitude.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::CoMRefSOUT |
Externalize the CoM reference.
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::comSIN |
Take the current CoM.
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::comStateSIN |
Take the current CoM state (pos, vel, acc).
| SignalTimeDependent<int, int> dynamicgraph::sot::PatternGenerator::contactPhaseSOUT |
Int Vector of support phase: leftFoot=1, rightFoot=-1, doubleSupport=0 (see enum).
| SignalTimeDependent<unsigned int, int> dynamicgraph::sot::PatternGenerator::dataInProcessSOUT |
true iff PG is processing. Use it for synchronize.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::dcomattitudeSOUT |
Externalize the dcom attitude.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::dCoMRefSOUT |
Externalize the CoM reference.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::ddcomattitudeSOUT |
Externalize the ddcom attitude.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::ddCoMRefSOUT |
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::dotLeftFootRefSOUT |
Externalize the left foot position reference.
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::dotRightFootRefSOUT |
Externalize the right foot position reference.
|
static |
Specify that the frame is expressed in the robot ego centered frame.
| SignalTimeDependent<Dummy, int> dynamicgraph::sot::PatternGenerator::firstSINTERN |
Internal signal for initialization and one shot signals.
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::FlyingFootRefSOUT |
Externalize the foot which is not considered as support foot, the information are given in a relative referentiel.
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::forceSIN |
Take the current external force applied to the com (fx, fy, fz).
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::forceSOUT |
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::InitCoMRefSOUT |
Externalize the initial CoM reference.
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::InitLeftFootRefSOUT |
Externalize the left foot position reference.
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::InitRightFootRefSOUT |
Externalize the right foot position reference.
| SignalTimeDependent<VectorRollPitchYaw, int> dynamicgraph::sot::PatternGenerator::InitWaistAttRefSOUT |
Externalize the initial Waist reference.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::InitWaistPosRefSOUT |
Externalize the initial Waist reference.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::InitZMPRefSOUT |
Externalize the initial ZMP reference .
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::jointPositionSIN |
Real state position values.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::jointWalkingErrorPositionSOUT |
Externalize the joint values for walking.
|
static |
Specify that the frame is expressed in the left foot centered frame.
| SignalTimeDependent<bool, int> dynamicgraph::sot::PatternGenerator::leftFootContactSOUT |
Booleans for contact of the feet.
| SignalPtr<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::LeftFootCurrentPosSIN |
Take the current left foot homogeneous position.
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::LeftFootRefSOUT |
Externalize the left foot position reference.
|
protected |
Distance between ankle and soil.
| std::deque<dynamicgraph::Vector> dynamicgraph::sot::PatternGenerator::m_bufferForce |
|
protected |
Com Attitude: does not really exist apart from when the robot is seen as an inverted pendulum.
|
protected |
Absolute position of the reference CoM.
|
protected |
Current support/contact phase defined by enum: leftFoot=1, rightFoot=-1, doubleSupport=0.
|
protected |
count for subsampling.
| dynamicgraph::Vector dynamicgraph::sot::PatternGenerator::m_currentForces |
|
protected |
true iff the pattern if dealing with data, false if pg is not working anymore/yet.
|
protected |
dCom Attitude: does not really exist apart when the robot is seen as an inverted pendulum
|
protected |
Absolute position of the reference dCoM.
|
protected |
ddCom Attitude: does not really exist apart when the robot is seen as an inverted pendulum
|
protected |
Absolute position of the reference ddCoM.
|
protected |
Absolute Derivate for the left and right feet.
|
protected |
|
protected |
|
protected |
Booleans used to indicate if feedback signals shoul be used or not.
| std::vector<double> dynamicgraph::sot::PatternGenerator::m_filterWindow |
|
protected |
Relative Position of the flying foot.
|
protected |
Booleans used to indicate if force feedback signals shoul be used or not.
|
protected |
Boolean variable to initialize the object by loading an object.
|
protected |
Initial Absolute position of the reference CoM.
| dynamicgraph::Vector dynamicgraph::sot::PatternGenerator::m_initForce |
|
protected |
|
protected |
Initial Absolute Starting Position for the left and right feet.
|
protected |
Boolean variable to initialize the position: first through the real state of the robot, then through the motor command.
|
protected |
|
protected |
|
protected |
|
protected |
Initial Absolute position and attitude of the reference Waist.
|
protected |
Initial Absolute position of the reference ZMP.
|
protected |
Joint values for walking.
|
protected |
Rigit motion between two waist positions at the beginning of the walking and at the end of the walking.
|
protected |
|
protected |
|
protected |
|
protected |
Absolute Position for the left and right feet.
|
protected |
iteration time.
|
protected |
Keep track of the motion between sequence of motions.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Pointer towards the interface of the pattern generator.
|
protected |
Pointer towards the robot model inside jrl-walkgen.
|
protected |
Some information related to the preview control.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Keep the frame reference.
|
protected |
|
protected |
|
protected |
Booleans used to indicate feet contacts.
|
protected |
|
protected |
The pointor toward the robot data.
|
protected |
The model of the robot.
|
protected |
Lenght of the sole.
|
protected |
Width of the sole.
|
protected |
Directory+Name where the SRDF file of the robot's model is located.
|
protected |
Integer for the support foot.
|
protected |
Time step.
|
protected |
trigger to start walking
|
protected |
Directory+Name where the URDF file of the robot's model is located.
|
protected |
Velocity reference for Herdt's PG.
|
protected |
Waist Attitude.
|
protected |
Waist Attitude Absolute.
|
protected |
Waist Attitude Homogeneous Matrix.
|
protected |
Waist position.
|
protected |
Waist position Absolute.
|
protected |
|
protected |
Directory+Name where the Rank of the joints are notified.
|
protected |
Storing the previous ZMP value.
|
protected |
Absolute position of the reference ZMP.
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::motorControlJointPositionSIN |
Motor control joint position values.
| SignalTimeDependent<Dummy, int> dynamicgraph::sot::PatternGenerator::OneStepOfControlS |
Internal signal to trigger one step of the algorithm.
| SignalTimeDependent<bool, int> dynamicgraph::sot::PatternGenerator::rightFootContactSOUT |
| SignalPtr<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::RightFootCurrentPosSIN |
Take the current right foot homogeneous position.
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::RightFootRefSOUT |
Externalize the right foot position reference.
|
protected |
| SignalTimeDependent<int, int> dynamicgraph::sot::PatternGenerator::SupportFootSOUT |
Externalize the support foot.
| SignalPtr<bool, int> dynamicgraph::sot::PatternGenerator::triggerSIN |
Take the current trigger to start OneStepOfControl.
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::velocitydesSIN |
Take the current desired velocity.
|
static |
Specify that the frame is expressed in the waist centered frame.
| SignalTimeDependent<VectorRollPitchYaw, int> dynamicgraph::sot::PatternGenerator::waistattitudeabsoluteSOUT |
Externalize the absolute waist attitude.
| SignalTimeDependent<MatrixHomogeneous, int> dynamicgraph::sot::PatternGenerator::waistattitudematrixabsoluteSOUT |
Externalize the absolute waist attitude into a homogeneous matrix.
| SignalTimeDependent<VectorRollPitchYaw, int> dynamicgraph::sot::PatternGenerator::waistattitudeSOUT |
Externalize the waist attitude.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::waistpositionabsoluteSOUT |
Externalize the absolute waist position.
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::waistpositionSOUT |
Externalize the waist position.
|
static |
Specify that the frame is expressed in the world reference frame.
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::ZMPPreviousControllerSIN |
Previous ZMP value (ZMP send by the preceding controller).
| SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::ZMPRefSOUT |
Externalize the ZMP reference .
| SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::PatternGenerator::zmpSIN |
Take the current zmp (x, y, z).