Public Member Functions |
void | enforceSafety () |
| Modify the commanded_effort_ of each joint state so that the joint limits are satisfied.
|
JointState * | getJointState (const std::string &name) |
| Get a joint state by name.
|
const JointState * | getJointState (const std::string &name) const |
| Get a const joint state by name.
|
ros::Time | getTime () |
| Get the time when the current controller cycle was started.
|
bool | isHalted () |
| Checks if one (or more) of the motors are halted.
|
void | propagateActuatorEffortToJointEffort () |
| Propagete the actuator efforts, through the transmissions, to the joint efforts.
|
void | propagateActuatorPositionToJointPosition () |
| Propagete the actuator positions, through the transmissions, to the joint positions.
|
void | propagateJointEffortToActuatorEffort () |
| Propagete the joint efforts, through the transmissions, to the actuator efforts.
|
void | propagateJointPositionToActuatorPosition () |
| Propagete the joint positions, through the transmissions, to the actuator positions.
|
| RobotState (Robot *model) |
| constructor
|
void | zeroCommands () |
| Set the commanded_effort_ of each joint state to zero.
|
Public Attributes |
std::vector< JointState > | joint_states_ |
| The vector of joint states, in no particular order.
|
std::map< std::string,
JointState * > | joint_states_map_ |
Robot * | model_ |
| The robot model containing the transmissions, urdf robot model, and hardware interface.
|
std::vector< std::vector
< pr2_hardware_interface::Actuator * > > | transmissions_in_ |
std::vector< std::vector
< pr2_mechanism_model::JointState * > > | transmissions_out_ |
This class provides the controllers with an interface to the robot state.
Most controllers that need the robot state should use the joint states, to get access to the joint position/velocity/effort, and to command the effort a joint should apply. Controllers can get access to the hard realtime clock through getTime()
Some specialized controllers (such as the calibration controllers) can get access to actuator states, and transmission states.
Definition at line 134 of file robot.h.