![]() |
NimbRo ROS Soccer Package
|
Base implementation of a gait engine, made to work with the Gait
motion module.
More...
#include <gait_engine.h>
Public Member Functions | |
GaitEngine () | |
Default constructor. | |
virtual | ~GaitEngine () |
Default destructor. | |
virtual void | reset () |
Reset the gait engine. More... | |
virtual void | updateHaltPose () |
Update the halt pose desired by the gait engine. More... | |
virtual void | step () |
Main step function of the gait engine. More... | |
virtual void | setOdometry (double posX, double posY, double rotZ) |
Set the CoM odometry to a particular 2D position and orientation. More... | |
virtual void | updateOdometry () |
Force an update of the CoM odometry in terms of 3D position and orientation. More... | |
virtual void | handleJoystickButton (int button) |
Notify the gait engine that a particular joystick button has been pressed and released by the user. More... | |
Public Attributes | |
GaitEngineInput | in |
Gait engine input data struct. | |
GaitEngineOutput | out |
Gait engine output data struct. | |
Protected Member Functions | |
void | resetBase () |
Reset the GaitEngine base class. More... | |
Protected Attributes | |
const robotcontrol::RobotModel * | model |
Pointer to the RobotModel object to use for retrieving state information in each step. More... | |
double | haltJointCmd [NUM_JOINTS] |
Commanded halt position for each joint (indexed by the JointID enum, in rad ). | |
double | haltJointEffort [NUM_JOINTS] |
Commanded halt joint effort (indexed by the JointID enum, in the range [0,1] ). | |
bool | haltUseRawJointCmds |
Apply the joint commands directly to the hardware in the halt pose, without using compensation or actuator controller(s) in-between. | |
const Gait * | m_gait |
Friends | |
class | Gait |
Base implementation of a gait engine, made to work with the Gait
motion module.
|
inlinevirtual |
Notify the gait engine that a particular joystick button has been pressed and released by the user.
This function should not attempt to access or write to the in
and out
members. button
is the index of the button that was pressed, generally in the range 5 to 12. The buttons that are reserved for use by the gait (buttons 1-4) are not ever passed to this function.
Reimplemented in cap_gait::CapGait.
|
inlinevirtual |
Reset the gait engine.
This function is used by the Gait
class, in conjunction with the resetBase()
function, to reset the GaitEngine object in terms of both its derived and base components respectively. This function must be able to clean up and reset the gait engine instance, no matter what state it is currently in.
Reimplemented in cap_gait::CapGait.
|
inlineprotected |
Reset the GaitEngine base class.
This function is used by the Gait
class, in conjunction with the virtual reset()
function, to reset the GaitEngine object in terms of both its base and derived components respectively.
|
virtual |
Set the CoM odometry to a particular 2D position and orientation.
Specifies the required (x,y)
position and yaw rotation for the CoM odometry. How exactly the yaw parameter is interpreted in the light of additional pitch and roll rotations is up to the implementation. It is recommended that the parameter is treated as fused yaw. Ideally, after calling this function the next retrieval of the robot odometry should reveal exactly posX
and posY
in the position vector (see GaitEngineOutput::odomPosition
). If you override this function then you need to override updateOdometry
too.
Reimplemented in cap_gait::CapGait.
|
virtual |
Main step function of the gait engine.
The step function is called in every execution cycle that the gait is required to be active. The command inputs for the gait engine can be retrieved from the in
class member, which ideally should only be read from, and the outputs of the gait engine should be written into the out
class member. Ideally all members of the out
struct should be written to from within the step()
function, as the members may contain arbitrary values until written to. The latest robot state information can be read from the model
class member, which is a const pointer to the required RobotModel object. The pointer is guaranteed to be valid before the step()
function is called for the first time.
Reimplemented in cap_gait::CapGait.
|
virtual |
Update the halt pose desired by the gait engine.
This function should update the halt pose of the gait engine if/as required. The halt pose is stored in three variables, namely haltJointCmd, haltJointEffort and haltUseRawJointCmds. This should be the robot pose from which the gait engine is nominally intended to be started and stopped from. The halt pose should normally be relatively constant during execution, but may for example depend on configuration parameters, and so is allowed to dynamically change.
This function is intended for use by the gait engine itself as well, such as for example at the beginning of the derived step()
function override. Make no assumptions about when this function is called externally.
Reimplemented in cap_gait::CapGait.
|
virtual |
Force an update of the CoM odometry in terms of 3D position and orientation.
This function should update the GaitEngineOutput::odomPosition
and GaitEngineOutput::odomOrientation
members of the out
member of the GaitEngine
class. Most of the time these two data fields will already be up-to-date anyway, but after calling this function the caller should be able to take for granted that the odometry stored in out
is up-to-date, and some valid value. The default implementation simply writes the last set odometry (setOdometry
) into the fields.
Reimplemented in cap_gait::CapGait.
|
protected |
Pointer to the RobotModel object to use for retrieving state information in each step.
This parameter is guaranteed to be set by the Gait
class prior to any other function being called. For obvious reasons it is heavily discouraged for a gait engine to write to this variable.