33 #ifndef JOINT_HANDLER_H 34 #define JOINT_HANDLER_H 40 #include "control_msgs/FollowJointTrajectoryFeedback.h" 41 #include "sensor_msgs/JointState.h" 48 namespace joint_relay_handler
104 control_msgs::FollowJointTrajectoryFeedback* control_state,
105 sensor_msgs::JointState* sensor_state);
116 virtual bool transform(
const std::vector<double>& pos_in, std::vector<double>* pos_out)
132 virtual bool select(
const std::vector<double>& all_joint_pos,
const std::vector<std::string>& all_joint_names,
133 std::vector<double>* pub_joint_pos, std::vector<std::string>* pub_joint_names);
bool init(industrial::smpl_msg_connection::SmplMsgConnection *connection, std::vector< std::string > &joint_names)
Class initializer.
virtual bool create_messages(JointMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
Convert joint message into publish message-types.
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 join...
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.
ros::Publisher pub_joint_control_state_
JointRelayHandler()
Constructor.
bool internalCB(JointMessage &in)
Callback executed upon receiving a joint message.
bool init(int msg_type, industrial::smpl_msg_connection::SmplMsgConnection *connection)
Message handler that relays joint positions (converts simple message types to ROS message types and p...
std::vector< std::string > all_joint_names_
ros::Publisher pub_joint_sensor_state_