54 #include <hardware_interface/hardware_interface.h> 62 template <
class T>
class ClassLoader;
88 bool initXml(TiXmlElement *root);
97 int getTransmissionIndex(
const std::string &name)
const;
139 JointState *getJointState(
const std::string &name);
142 const JointState *getJointState(
const std::string &name)
const;
162 void propagateActuatorPositionToJointPosition();
164 void propagateJointPositionToActuatorPosition();
167 void propagateJointEffortToActuatorEffort();
169 void propagateActuatorEffortToJointEffort();
172 void enforceSafety();
std::vector< boost::shared_ptr< Transmission > > transmissions_
The list of transmissions.
pr2_hardware_interface::HardwareInterface * hw_
a pointer to the pr2 hardware interface. Only for advanced users
ros::Time getTime()
Get the time when the current controller cycle was started.
This class provides the controllers with an interface to the robot state.
Robot * model_
The robot model containing the transmissions, urdf robot model, and hardware interface.
std::vector< std::vector< pr2_mechanism_model::JointState * > > transmissions_out_
std::vector< JointState > joint_states_
The vector of joint states, in no particular order.
std::map< std::string, JointState * > joint_states_map_
boost::shared_ptr< pluginlib::ClassLoader< pr2_mechanism_model::Transmission > > transmission_loader_
std::vector< std::vector< pr2_hardware_interface::Actuator * > > transmissions_in_
This class provides the controllers with an interface to the robot model.
urdf::Model robot_model_
The kinematic/dynamic model of the robot.