This class provides the controllers with an interface to the robot model. More...
#include <robot.h>
Public Member Functions | |
| pr2_hardware_interface::Actuator * | getActuator (const std::string &name) const |
| get an actuator pointer based on the actuator name. Returns NULL on failure More... | |
| ros::Time | getTime () |
| Get the time when the current controller cycle was started. More... | |
| boost::shared_ptr< pr2_mechanism_model::Transmission > | getTransmission (const std::string &name) const |
| get a transmission pointer based on the transmission name. Returns NULL on failure More... | |
| int | getTransmissionIndex (const std::string &name) const |
| get the transmission index based on the transmission name. Returns -1 on failure More... | |
| bool | initXml (TiXmlElement *root) |
| Initialize the robot model form xml. More... | |
| Robot (pr2_hardware_interface::HardwareInterface *hw) | |
| Constructor. More... | |
| ~Robot () | |
| Destructor. More... | |
Public Attributes | |
| pr2_hardware_interface::HardwareInterface * | hw_ |
| a pointer to the pr2 hardware interface. Only for advanced users More... | |
| urdf::Model | robot_model_ |
| The kinematic/dynamic model of the robot. More... | |
| std::vector< boost::shared_ptr< Transmission > > | transmissions_ |
| The list of transmissions. More... | |
Private Attributes | |
| boost::shared_ptr< pluginlib::ClassLoader< pr2_mechanism_model::Transmission > > | transmission_loader_ |
This class provides the controllers with an interface to the robot model.
Most controllers that need the robot model should use the 'robot_model_', which is a kinematic/dynamic model of the robot, represented by a KDL Tree structure.
Some specialized controllers (such as the calibration controllers) can get access to actuators, transmissions and special joint parameters.
| Robot::Robot | ( | pr2_hardware_interface::HardwareInterface * | hw | ) |
| Actuator * Robot::getActuator | ( | const std::string & | name | ) | const |
| ros::Time Robot::getTime | ( | ) |
| boost::shared_ptr< Transmission > Robot::getTransmission | ( | const std::string & | name | ) | const |
| int Robot::getTransmissionIndex | ( | const std::string & | name | ) | const |
| bool Robot::initXml | ( | TiXmlElement * | root | ) |
| pr2_hardware_interface::HardwareInterface* pr2_mechanism_model::Robot::hw_ |
| urdf::Model pr2_mechanism_model::Robot::robot_model_ |
|
private |
| std::vector<boost::shared_ptr<Transmission> > pr2_mechanism_model::Robot::transmissions_ |