Message handler that relays joint positions (converts simple message types to ROS message types and publishes them) More...
#include <joint_feedback_ex_relay_handler.h>
Public Member Functions | |
virtual bool | init (SmplMsgConnection *connection, std::vector< std::string > &joint_names) |
Class initializer. | |
virtual bool | init (SmplMsgConnection *connection, std::map< int, RobotGroup > &robot_groups) |
Class initializer. | |
JointFeedbackExRelayHandler (int groups_number=-1) | |
Constructor. | |
Protected Member Functions | |
virtual bool | convert_message (JointFeedbackMessage &msg_in, DynamicJointsGroup *joint_state, int robot_id) |
Convert joint message into intermediate message-type. | |
bool | create_messages (SimpleMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state) |
Convert joint message into publish message-types. | |
bool | create_messages (JointFeedbackMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state, int robot_id) |
Protected Attributes | |
ros::Publisher | dynamic_pub_joint_control_state_ |
int | groups_number_ |
ros::Publisher | pub_joint_control_state_ |
ros::Publisher | pub_joint_sensor_state_ |
bool | version_0_ |
Private Member Functions | |
bool | convert_message (JointFeedbackExMessage &msg_in, DynamicJointsGroup *joint_state, int robot_id) |
Convert joint feedback message into intermediate message-type. | |
Static Private Member Functions | |
static bool | JointDataToVector (const industrial::joint_data::JointData &joints, std::vector< double > &vec, int len) |
Private Attributes | |
industrial::shared_types::shared_int | valid_fields_from_message_ |
bit-mask of (optional) fields that have been initialized with valid data |
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 68 of file joint_feedback_ex_relay_handler.h.
industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::JointFeedbackExRelayHandler | ( | int | groups_number = -1 | ) | [inline] |
Constructor.
Definition at line 74 of file joint_feedback_ex_relay_handler.h.
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::convert_message | ( | JointFeedbackMessage & | msg_in, |
DynamicJointsGroup * | joint_state, | ||
int | robot_id | ||
) | [protected, virtual] |
Convert joint message into intermediate message-type.
[in] | msg_in | Message from robot connection |
[out] | joint_state | JointTrajectoryPt message for intermediate processing |
Definition at line 162 of file joint_feedback_ex_relay_handler.cpp.
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::convert_message | ( | JointFeedbackExMessage & | msg_in, |
DynamicJointsGroup * | joint_state, | ||
int | robot_id | ||
) | [private] |
Convert joint feedback message into intermediate message-type.
[in] | msg_in | JointFeedbackMessage from robot connection |
[out] | joint_state | JointTrajectoryPt message for intermediate processing |
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::create_messages | ( | SimpleMessage & | msg_in, |
control_msgs::FollowJointTrajectoryFeedback * | control_state, | ||
sensor_msgs::JointState * | sensor_state | ||
) | [protected, virtual] |
Convert joint message into publish message-types.
[in] | msg_in | Message from robot connection |
[out] | control_state | FollowJointTrajectoryFeedback message for ROS publishing |
[out] | sensor_state | JointState message for ROS publishing |
Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.
Definition at line 83 of file joint_feedback_ex_relay_handler.cpp.
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::create_messages | ( | JointFeedbackMessage & | msg_in, |
control_msgs::FollowJointTrajectoryFeedback * | control_state, | ||
sensor_msgs::JointState * | sensor_state, | ||
int | robot_id | ||
) | [protected] |
Definition at line 111 of file joint_feedback_ex_relay_handler.cpp.
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::init | ( | SmplMsgConnection * | connection, |
std::vector< std::string > & | joint_names | ||
) | [virtual] |
Class initializer.
connection | simple message connection that will be used to send replies. |
joint_names | list of joint-names for msg-publishing.
|
Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.
Definition at line 71 of file joint_feedback_ex_relay_handler.cpp.
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::init | ( | SmplMsgConnection * | connection, |
std::map< int, RobotGroup > & | robot_groups | ||
) | [virtual] |
Class initializer.
connection | simple message connection that will be used to send replies. |
joint_names | list of joint-names for msg-publishing.
|
Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.
Definition at line 51 of file joint_feedback_ex_relay_handler.cpp.
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::JointDataToVector | ( | const industrial::joint_data::JointData & | joints, |
std::vector< double > & | vec, | ||
int | len | ||
) | [static, private] |
Definition at line 236 of file joint_feedback_ex_relay_handler.cpp.
ros::Publisher industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::dynamic_pub_joint_control_state_ [protected] |
Definition at line 98 of file joint_feedback_ex_relay_handler.h.
int industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::groups_number_ [protected] |
Definition at line 94 of file joint_feedback_ex_relay_handler.h.
ros::Publisher industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::pub_joint_control_state_ [protected] |
Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.
Definition at line 97 of file joint_feedback_ex_relay_handler.h.
ros::Publisher industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::pub_joint_sensor_state_ [protected] |
Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.
Definition at line 99 of file joint_feedback_ex_relay_handler.h.
industrial::shared_types::shared_int industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::valid_fields_from_message_ [private] |
bit-mask of (optional) fields that have been initialized with valid data
Definition at line 131 of file joint_feedback_ex_relay_handler.h.
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::version_0_ [protected] |
Definition at line 95 of file joint_feedback_ex_relay_handler.h.