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, std::vector< std::string > &joint_names) |
Class initializer. | |
JointRelayHandler () | |
Constructor. | |
Protected Member Functions | |
virtual bool | create_messages (JointMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state) |
Convert joint message into publish message-types. | |
bool | internalCB (JointMessage &in) |
Callback executed upon receiving a joint message. | |
virtual bool | select (const std::vector< double > &all_joint_pos, const std::vector< std::string > &all_joint_names, std::vector< double > *pub_joint_pos, std::vector< std::string > *pub_joint_names) |
Select specific joints for publishing. | |
virtual bool | transform (const std::vector< double > &pos_in, std::vector< double > *pos_out) |
Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific joint coupling. | |
Protected Attributes | |
std::vector< std::string > | all_joint_names_ |
ros::NodeHandle | node_ |
ros::Publisher | pub_joint_control_state_ |
ros::Publisher | pub_joint_sensor_state_ |
Private Member Functions | |
bool | internalCB (SimpleMessage &in) |
Callback executed upon receiving a message. |
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 61 of file joint_relay_handler.h.
Constructor.
Definition at line 71 of file joint_relay_handler.h.
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::create_messages | ( | JointMessage & | msg_in, |
control_msgs::FollowJointTrajectoryFeedback * | control_state, | ||
sensor_msgs::JointState * | sensor_state | ||
) | [protected, virtual] |
Convert joint message into publish message-types.
[in] | msg_in | Joint message from robot connection |
[out] | control_state | FollowJointTrajectoryFeedback message for ROS publishing |
[out] | sensor_state | JointState message for ROS publishing |
Definition at line 98 of file joint_relay_handler.cpp.
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::init | ( | industrial::smpl_msg_connection::SmplMsgConnection * | connection, |
std::vector< std::string > & | joint_names | ||
) |
Class initializer.
connection | simple message connection that will be used to send replies. |
joint_names | list of joint-names for msg-publishing.
|
Definition at line 46 of file joint_relay_handler.cpp.
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::internalCB | ( | JointMessage & | in | ) | [protected] |
Callback executed upon receiving a joint message.
in | incoming message |
Definition at line 72 of file joint_relay_handler.cpp.
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::internalCB | ( | SimpleMessage & | in | ) | [private, virtual] |
Callback executed upon receiving a message.
in | incoming message |
Implements industrial::message_handler::MessageHandler.
Definition at line 59 of file joint_relay_handler.cpp.
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::select | ( | const std::vector< double > & | all_joint_pos, |
const std::vector< std::string > & | all_joint_names, | ||
std::vector< double > * | pub_joint_pos, | ||
std::vector< std::string > * | pub_joint_names | ||
) | [protected, virtual] |
Select specific joints for publishing.
[in] | all_joint_pos | joint positions, in count/order matching robot connection |
[in] | all_joint_names | joint names, matching all_joint_pos |
[out] | pub_joint_pos | joint positions selected for publishing |
[out] | pub_joint_names | joint names selected for publishing |
Definition at line 146 of file joint_relay_handler.cpp.
virtual bool industrial_robot_client::joint_relay_handler::JointRelayHandler::transform | ( | const std::vector< double > & | pos_in, |
std::vector< double > * | pos_out | ||
) | [inline, protected, virtual] |
Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific joint coupling.
[in] | pos_in | joint positions, exactly as passed from robot connection. |
[out] | pos_out | transformed joint positions (in same order/count as input positions) |
Definition at line 116 of file joint_relay_handler.h.
std::vector<std::string> industrial_robot_client::joint_relay_handler::JointRelayHandler::all_joint_names_ [protected] |
Definition at line 88 of file joint_relay_handler.h.
Definition at line 92 of file joint_relay_handler.h.
ros::Publisher industrial_robot_client::joint_relay_handler::JointRelayHandler::pub_joint_control_state_ [protected] |
Definition at line 90 of file joint_relay_handler.h.
ros::Publisher industrial_robot_client::joint_relay_handler::JointRelayHandler::pub_joint_sensor_state_ [protected] |
Definition at line 91 of file joint_relay_handler.h.