Public Member Functions | Public Attributes | List of all members
pr2_mechanism_model::RobotState Class Reference

This class provides the controllers with an interface to the robot state. More...

#include <robot.h>

Inheritance diagram for pr2_mechanism_model::RobotState:
Inheritance graph
[legend]

Public Member Functions

void enforceSafety ()
 Modify the commanded_effort_ of each joint state so that the joint limits are satisfied. More...
 
JointStategetJointState (const std::string &name)
 Get a joint state by name. More...
 
const JointStategetJointState (const std::string &name) const
 Get a const joint state by name. More...
 
ros::Time getTime ()
 Get the time when the current controller cycle was started. More...
 
bool isHalted ()
 Checks if one (or more) of the motors are halted. More...
 
void propagateActuatorEffortToJointEffort ()
 Propagete the actuator efforts, through the transmissions, to the joint efforts. More...
 
void propagateActuatorPositionToJointPosition ()
 Propagete the actuator positions, through the transmissions, to the joint positions. More...
 
void propagateJointEffortToActuatorEffort ()
 Propagete the joint efforts, through the transmissions, to the actuator efforts. More...
 
void propagateJointPositionToActuatorPosition ()
 Propagete the joint positions, through the transmissions, to the actuator positions. More...
 
 RobotState (Robot *model)
 constructor More...
 
void zeroCommands ()
 Set the commanded_effort_ of each joint state to zero. More...
 
- Public Member Functions inherited from hardware_interface::HardwareInterface
virtual void claim (std::string resource)
 
virtual void claim (std::string resource)
 
void clearClaims ()
 
void clearClaims ()
 
std::set< std::string > getClaims () const
 
std::set< std::string > getClaims () const
 
virtual ~HardwareInterface ()=default
 

Public Attributes

std::vector< JointStatejoint_states_
 The vector of joint states, in no particular order. More...
 
std::map< std::string, JointState * > joint_states_map_
 
Robotmodel_
 The robot model containing the transmissions, urdf robot model, and hardware interface. More...
 
std::vector< std::vector< pr2_hardware_interface::Actuator * > > transmissions_in_
 
std::vector< std::vector< pr2_mechanism_model::JointState * > > transmissions_out_
 

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 126 of file robot.h.

Constructor & Destructor Documentation

◆ RobotState()

RobotState::RobotState ( Robot model)

constructor

Definition at line 158 of file robot.cpp.

Member Function Documentation

◆ enforceSafety()

void RobotState::enforceSafety ( )

Modify the commanded_effort_ of each joint state so that the joint limits are satisfied.

Definition at line 256 of file robot.cpp.

◆ getJointState() [1/2]

JointState * RobotState::getJointState ( const std::string &  name)

Get a joint state by name.

Definition at line 203 of file robot.cpp.

◆ getJointState() [2/2]

const JointState * RobotState::getJointState ( const std::string &  name) const

Get a const joint state by name.

Definition at line 212 of file robot.cpp.

◆ getTime()

ros::Time pr2_mechanism_model::RobotState::getTime ( )
inline

Get the time when the current controller cycle was started.

Definition at line 145 of file robot.h.

◆ isHalted()

bool RobotState::isHalted ( )

Checks if one (or more) of the motors are halted.

Definition at line 244 of file robot.cpp.

◆ propagateActuatorEffortToJointEffort()

void RobotState::propagateActuatorEffortToJointEffort ( )

Propagete the actuator efforts, through the transmissions, to the joint efforts.

Definition at line 279 of file robot.cpp.

◆ propagateActuatorPositionToJointPosition()

void RobotState::propagateActuatorPositionToJointPosition ( )

Propagete the actuator positions, through the transmissions, to the joint positions.

Definition at line 221 of file robot.cpp.

◆ propagateJointEffortToActuatorEffort()

void RobotState::propagateJointEffortToActuatorEffort ( )

Propagete the joint efforts, through the transmissions, to the actuator efforts.

Definition at line 235 of file robot.cpp.

◆ propagateJointPositionToActuatorPosition()

void RobotState::propagateJointPositionToActuatorPosition ( )

Propagete the joint positions, through the transmissions, to the actuator positions.

Definition at line 270 of file robot.cpp.

◆ zeroCommands()

void RobotState::zeroCommands ( )

Set the commanded_effort_ of each joint state to zero.

Definition at line 264 of file robot.cpp.

Member Data Documentation

◆ joint_states_

std::vector<JointState> pr2_mechanism_model::RobotState::joint_states_

The vector of joint states, in no particular order.

Definition at line 136 of file robot.h.

◆ joint_states_map_

std::map<std::string, JointState*> pr2_mechanism_model::RobotState::joint_states_map_

Definition at line 181 of file robot.h.

◆ model_

Robot* pr2_mechanism_model::RobotState::model_

The robot model containing the transmissions, urdf robot model, and hardware interface.

Definition at line 133 of file robot.h.

◆ transmissions_in_

std::vector<std::vector<pr2_hardware_interface::Actuator*> > pr2_mechanism_model::RobotState::transmissions_in_

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 145 of file robot.h.

◆ transmissions_out_

std::vector<std::vector<pr2_mechanism_model::JointState*> > pr2_mechanism_model::RobotState::transmissions_out_

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 159 of file robot.h.


The documentation for this class was generated from the following files:


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Tue Mar 7 2023 03:54:53