pr2_mechanism_model::RobotState Class Reference
This class provides the controllers with an interface to the robot state.
More...
#include <robot.h>
List of all members.
Public Member Functions |
void | enforceSafety () |
| Modify the commanded_effort_ of each joint state so that the joint limits are satisfied.
|
const JointState * | getJointState (const std::string &name) const |
| Get a const joint state by name.
|
JointState * | getJointState (const std::string &name) |
| Get a 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.
|
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_ |
Private Attributes |
std::map< std::string,
JointState * > | joint_states_map_ |
Detailed Description
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 133 of file robot.h.
Constructor & Destructor Documentation
RobotState::RobotState |
( |
Robot * |
model |
) |
|
Member Function Documentation
void RobotState::enforceSafety |
( |
|
) |
|
Modify the commanded_effort_ of each joint state so that the joint limits are satisfied.
Definition at line 266 of file robot.cpp.
const JointState * RobotState::getJointState |
( |
const std::string & |
name |
) |
const |
Get a const joint state by name.
Definition at line 222 of file robot.cpp.
JointState * RobotState::getJointState |
( |
const std::string & |
name |
) |
|
Get a joint state by name.
Definition at line 213 of file robot.cpp.
ros::Time pr2_mechanism_model::RobotState::getTime |
( |
|
) |
[inline] |
Get the time when the current controller cycle was started.
Definition at line 152 of file robot.h.
bool RobotState::isHalted |
( |
|
) |
|
Checks if one (or more) of the motors are halted.
Definition at line 254 of file robot.cpp.
void RobotState::propagateActuatorEffortToJointEffort |
( |
|
) |
|
Propagete the actuator efforts, through the transmissions, to the joint efforts.
Definition at line 289 of file robot.cpp.
void RobotState::propagateActuatorPositionToJointPosition |
( |
|
) |
|
Propagete the actuator positions, through the transmissions, to the joint positions.
Definition at line 231 of file robot.cpp.
void RobotState::propagateJointEffortToActuatorEffort |
( |
|
) |
|
Propagete the joint efforts, through the transmissions, to the actuator efforts.
Definition at line 245 of file robot.cpp.
void RobotState::propagateJointPositionToActuatorPosition |
( |
|
) |
|
Propagete the joint positions, through the transmissions, to the actuator positions.
Definition at line 280 of file robot.cpp.
void RobotState::zeroCommands |
( |
|
) |
|
Set the commanded_effort_ of each joint state to zero.
Definition at line 274 of file robot.cpp.
Member Data Documentation
The vector of joint states, in no particular order.
Definition at line 143 of file robot.h.
The robot model containing the transmissions, urdf robot model, and hardware interface.
Definition at line 140 of file robot.h.
Each transmission refers to the actuators and joints it connects by name. Since name lookup is slow, for each transmission in the robot model we cache pointers to the actuators and joints that it connects.
Definition at line 152 of file robot.h.
Each transmission refers to the actuators and joints it connects by name. Since name lookup is slow, for each transmission in the robot model we cache pointers to the actuators and joints that it connects.
Definition at line 166 of file robot.h.
The documentation for this class was generated from the following files: