Message handler that relays joint positions (converts simple message types to ROS message types and publishes them) More...
#include <joint_relay_handler.h>

| Public Member Functions | |
| bool | init (industrial::smpl_msg_connection::SmplMsgConnection *connection) | 
| Class initializer. | |
| bool | init (int msg_type, industrial::smpl_msg_connection::SmplMsgConnection *connection) | 
| Class initializer (Direct call to base class with the same name) I couldn't get the "using" form to work/. | |
| JointRelayHandler (ros::NodeHandle &n) | |
| Constructor. | |
| Private Member Functions | |
| bool | internalCB (industrial::simple_message::SimpleMessage &in) | 
| Callback executed upon receiving a ping message. | |
| Private Attributes | |
| control_msgs::FollowJointTrajectoryFeedback | joint_control_state_ | 
| sensor_msgs::JointState | joint_sensor_state_ | 
| ros::NodeHandle | node_ | 
| ros::Publisher | pub_joint_control_state_ | 
| ros::Publisher | pub_joint_sensor_state_ | 
| Static Private Attributes | |
| static const int | NUM_OF_JOINTS_ = 7 | 
Message handler that relays joint positions (converts simple message types to ROS message types and publishes them)
THIS CLASS IS NOT THREAD-SAFE
Definition at line 59 of file joint_relay_handler.h.
Constructor.
| ROS | node handle (used for publishing) | 
Definition at line 46 of file joint_relay_handler.cpp.
| bool motoman::joint_relay_handler::JointRelayHandler::init | ( | industrial::smpl_msg_connection::SmplMsgConnection * | connection | ) | 
Class initializer.
| connection | simple message connection that will be used to send replies. | 
Definition at line 78 of file joint_relay_handler.cpp.
| bool motoman::joint_relay_handler::JointRelayHandler::init | ( | int | msg_type, | 
| industrial::smpl_msg_connection::SmplMsgConnection * | connection | ||
| ) |  [inline] | 
Class initializer (Direct call to base class with the same name) I couldn't get the "using" form to work/.
| connection | simple message connection that will be used to send replies. | 
Reimplemented from industrial::message_handler::MessageHandler.
Definition at line 89 of file joint_relay_handler.h.
| bool motoman::joint_relay_handler::JointRelayHandler::internalCB | ( | industrial::simple_message::SimpleMessage & | in | ) |  [private, virtual] | 
Callback executed upon receiving a ping message.
| in | incoming message | 
Implements industrial::message_handler::MessageHandler.
Definition at line 83 of file joint_relay_handler.cpp.
| control_msgs::FollowJointTrajectoryFeedback motoman::joint_relay_handler::JointRelayHandler::joint_control_state_  [private] | 
Definition at line 90 of file joint_relay_handler.h.
| sensor_msgs::JointState motoman::joint_relay_handler::JointRelayHandler::joint_sensor_state_  [private] | 
Definition at line 97 of file joint_relay_handler.h.
Definition at line 100 of file joint_relay_handler.h.
| const int motoman::joint_relay_handler::JointRelayHandler::NUM_OF_JOINTS_ = 7  [static, private] | 
Definition at line 102 of file joint_relay_handler.h.
Definition at line 98 of file joint_relay_handler.h.
Definition at line 99 of file joint_relay_handler.h.