Public Member Functions | Public Attributes
ros_ethercat_model::RobotState Class Reference

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

#include <robot_state.hpp>

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

List of all members.

Public Member Functions

ActuatorgetActuator (const std::string &name)
 get an actuator by actuator name or NULL on failure
CustomHWgetCustomHW (const std::string &name)
 Get Custom Hardware device by name or NULL on failure.
JointStategetJointState (const std::string &name)
 Get a joint state by name or NULL on failure.
ros::Time getTime ()
 return the current time of the control loop
void initXml (TiXmlElement *root)
void propagateActuatorPositionToJointPosition ()
 Propagate the actuator positions, through the transmissions, to the joint positions.
void propagateJointEffortToActuatorEffort ()
 Propagate the joint efforts, through the transmissions, to the actuator efforts.
 RobotState (TiXmlElement *root=NULL)

Public Attributes

ros::Time current_time_
 The time at which the commands were sent to the hardware.
boost::ptr_unordered_map
< std::string, CustomHW
custom_hws_
 Custom hardware structures mapped to their names.
std::map< std::string,
std::string > 
device_to_name_map_
boost::ptr_unordered_map
< std::string, JointState
joint_states_
 The joint states mapped to the joint names.
urdf::Model robot_model_
 The kinematic/dynamic model of the robot.
pluginlib::ClassLoader
< Transmission
transmission_loader_
 the transmission's loader
boost::ptr_vector< Transmissiontransmissions_
 the robot's transmissions

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 current_time_

Definition at line 63 of file robot_state.hpp.


Constructor & Destructor Documentation

ros_ethercat_model::RobotState::RobotState ( TiXmlElement *  root = NULL) [inline]

Definition at line 66 of file robot_state.hpp.


Member Function Documentation

Actuator* ros_ethercat_model::RobotState::getActuator ( const std::string &  name) [inline]

get an actuator by actuator name or NULL on failure

Definition at line 134 of file robot_state.hpp.

CustomHW* ros_ethercat_model::RobotState::getCustomHW ( const std::string &  name) [inline]

Get Custom Hardware device by name or NULL on failure.

Definition at line 143 of file robot_state.hpp.

JointState* ros_ethercat_model::RobotState::getJointState ( const std::string &  name) [inline]

Get a joint state by name or NULL on failure.

Definition at line 149 of file robot_state.hpp.

return the current time of the control loop

Definition at line 155 of file robot_state.hpp.

void ros_ethercat_model::RobotState::initXml ( TiXmlElement *  root) [inline]

Definition at line 73 of file robot_state.hpp.

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

Definition at line 120 of file robot_state.hpp.

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

Definition at line 127 of file robot_state.hpp.


Member Data Documentation

The time at which the commands were sent to the hardware.

Definition at line 161 of file robot_state.hpp.

boost::ptr_unordered_map<std::string, CustomHW> ros_ethercat_model::RobotState::custom_hws_

Custom hardware structures mapped to their names.

Definition at line 167 of file robot_state.hpp.

std::map<std::string, std::string> ros_ethercat_model::RobotState::device_to_name_map_

Definition at line 179 of file robot_state.hpp.

boost::ptr_unordered_map<std::string, JointState> ros_ethercat_model::RobotState::joint_states_

The joint states mapped to the joint names.

Definition at line 164 of file robot_state.hpp.

The kinematic/dynamic model of the robot.

Definition at line 170 of file robot_state.hpp.

the transmission's loader

Definition at line 176 of file robot_state.hpp.

the robot's transmissions

Definition at line 173 of file robot_state.hpp.


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


ros_ethercat_model
Author(s): Manos Nikolaidis
autogenerated on Thu Jul 4 2019 20:01:55