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

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

#include <robot.h>

Public Member Functions

pr2_hardware_interface::ActuatorgetActuator (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::TransmissiongetTransmission (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::HardwareInterfacehw_
 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_
 

Detailed Description

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.

Definition at line 78 of file robot.h.

Constructor & Destructor Documentation

◆ Robot()

Constructor.

Definition at line 46 of file robot.cpp.

◆ ~Robot()

pr2_mechanism_model::Robot::~Robot ( )
inline

Destructor.

Definition at line 85 of file robot.h.

Member Function Documentation

◆ getActuator()

Actuator * Robot::getActuator ( const std::string &  name) const

get an actuator pointer based on the actuator name. Returns NULL on failure

Definition at line 143 of file robot.cpp.

◆ getTime()

ros::Time Robot::getTime ( )

Get the time when the current controller cycle was started.

Definition at line 121 of file robot.cpp.

◆ getTransmission()

boost::shared_ptr< Transmission > Robot::getTransmission ( const std::string &  name) const

get a transmission pointer based on the transmission name. Returns NULL on failure

Definition at line 148 of file robot.cpp.

◆ getTransmissionIndex()

int Robot::getTransmissionIndex ( const std::string &  name) const

get the transmission index based on the transmission name. Returns -1 on failure

Definition at line 138 of file robot.cpp.

◆ initXml()

bool Robot::initXml ( TiXmlElement *  root)

Initialize the robot model form xml.

Definition at line 51 of file robot.cpp.

Member Data Documentation

◆ hw_

pr2_hardware_interface::HardwareInterface* pr2_mechanism_model::Robot::hw_

a pointer to the pr2 hardware interface. Only for advanced users

Definition at line 109 of file robot.h.

◆ robot_model_

urdf::Model pr2_mechanism_model::Robot::robot_model_

The kinematic/dynamic model of the robot.

Definition at line 91 of file robot.h.

◆ transmission_loader_

boost::shared_ptr<pluginlib::ClassLoader<pr2_mechanism_model::Transmission> > pr2_mechanism_model::Robot::transmission_loader_
private

Definition at line 112 of file robot.h.

◆ transmissions_

std::vector<boost::shared_ptr<Transmission> > pr2_mechanism_model::Robot::transmissions_

The list of transmissions.

Definition at line 94 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