Message handler that relays joint positions (converts simple message types to ROS message types and publishes them) More...
#include <wrench_relay_handler.h>
Public Member Functions | |
bool | init (industrial::smpl_msg_connection::SmplMsgConnection *connection) |
Class initializer. More... | |
WrenchRelayHandler () | |
Constructor. More... | |
Protected Member Functions | |
bool | internalCB (fsrobo_r_driver::simple_message::wrench_message::WrenchMessage &in) |
Callback executed upon receiving a robot status message. More... | |
Protected Attributes | |
ros::NodeHandle | node_ |
ros::Publisher | pub_wrench_stamped_ |
Private Member Functions | |
bool | internalCB (industrial::simple_message::SimpleMessage &in) |
Callback executed upon receiving a message. More... | |
Private Attributes | |
std::string | force_frame_id_ |
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 49 of file wrench_relay_handler.h.
|
inline |
Constructor.
Definition at line 59 of file wrench_relay_handler.h.
bool fsrobo_r_driver::wrench_relay_handler::WrenchRelayHandler::init | ( | industrial::smpl_msg_connection::SmplMsgConnection * | connection | ) |
Class initializer.
connection | simple message connection that will be used to send replies. |
Definition at line 45 of file wrench_relay_handler.cpp.
|
protected |
Callback executed upon receiving a robot status message.
in | incoming message |
Definition at line 66 of file wrench_relay_handler.cpp.
|
privatevirtual |
Callback executed upon receiving a message.
in | incoming message |
Implements industrial::message_handler::MessageHandler.
Definition at line 53 of file wrench_relay_handler.cpp.
|
private |
Definition at line 94 of file wrench_relay_handler.h.
|
protected |
Definition at line 74 of file wrench_relay_handler.h.
|
protected |
Definition at line 73 of file wrench_relay_handler.h.