34 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H 35 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H 43 #include "motoman_msgs/DynamicJointsGroup.h" 44 #include "motoman_msgs/DynamicJointTrajectoryFeedback.h" 48 namespace joint_feedback_ex_relay_handler
57 using trajectory_msgs::JointTrajectoryPoint;
58 using motoman_msgs::DynamicJointsGroup;
59 using motoman_msgs::DynamicJointTrajectoryFeedback;
88 std::vector<std::string> &joint_names);
91 std::map<int, RobotGroup> &robot_groups);
113 control_msgs::FollowJointTrajectoryFeedback* control_state,
114 sensor_msgs::JointState* sensor_state);
118 control_msgs::FollowJointTrajectoryFeedback* control_state,
119 sensor_msgs::JointState* sensor_state,
int robot_id);
123 std::vector<double> &vec,
int len);
144 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H Message handler that relays joint positions (converts simple message types to ROS message types and p...
virtual bool init(SmplMsgConnection *connection, std::vector< std::string > &joint_names)
Class initializer.
Class encapsulated joint feedback ex message generation methods (either to or from a industrial::simp...
virtual bool convert_message(JointFeedbackMessage &msg_in, DynamicJointsGroup *joint_state, int robot_id)
Convert joint message into intermediate message-type.
static bool JointDataToVector(const industrial::joint_data::JointData &joints, std::vector< double > &vec, int len)
industrial::shared_types::shared_int valid_fields_from_message_
bit-mask of (optional) fields that have been initialized with valid data
ros::Publisher dynamic_pub_joint_control_state_
ros::Publisher pub_joint_sensor_state_
ros::Publisher pub_joint_control_state_
bool create_messages(SimpleMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
Convert joint message into publish message-types.
Message handler that relays joint positions (converts simple message types to ROS message types and p...
JointFeedbackExRelayHandler(int groups_number=-1)
Constructor.
Message handler that relays joint positions (converts simple message types to ROS message types and p...