Go to the documentation of this file.00001 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H
00002 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H
00003
00004 #include <vector>
00005 #include <map>
00006 #include <string>
00007 #include "motoman_driver/industrial_robot_client/joint_relay_handler.h"
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #include "motoman_driver/industrial_robot_client/joint_feedback_relay_handler.h"
00042 #include "motoman_driver/simple_message/messages/joint_feedback_ex_message.h"
00043 #include "motoman_msgs/DynamicJointsGroup.h"
00044 #include "motoman_msgs/DynamicJointTrajectoryFeedback.h"
00045
00046 namespace industrial_robot_client
00047 {
00048 namespace joint_feedback_ex_relay_handler
00049 {
00050
00051 using industrial::joint_feedback_ex_message::JointFeedbackExMessage;
00052 using industrial::joint_feedback_message::JointFeedbackMessage;
00053 using industrial::simple_message::SimpleMessage;
00054 using industrial::smpl_msg_connection::SmplMsgConnection;
00055 using industrial_robot_client::joint_relay_handler::JointRelayHandler;
00056 using industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler;
00057 using trajectory_msgs::JointTrajectoryPoint;
00058 using motoman_msgs::DynamicJointsGroup;
00059 using motoman_msgs::DynamicJointTrajectoryFeedback;
00060
00068 class JointFeedbackExRelayHandler : public industrial_robot_client::joint_relay_handler::JointRelayHandler
00069 {
00070 public:
00074 JointFeedbackExRelayHandler(int groups_number = -1) : groups_number_(groups_number) {};
00075
00076
00087 virtual bool init(SmplMsgConnection* connection,
00088 std::vector<std::string> &joint_names);
00089
00090 virtual bool init(SmplMsgConnection* connection,
00091 std::map<int, RobotGroup> &robot_groups);
00092
00093 protected:
00094 int groups_number_;
00095 bool version_0_;
00096
00097 ros::Publisher pub_joint_control_state_;
00098 ros::Publisher dynamic_pub_joint_control_state_;
00099 ros::Publisher pub_joint_sensor_state_;
00100
00109 virtual bool convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00110
00111
00112 bool create_messages(SimpleMessage& msg_in,
00113 control_msgs::FollowJointTrajectoryFeedback* control_state,
00114 sensor_msgs::JointState* sensor_state);
00115
00116
00117 bool create_messages(JointFeedbackMessage& msg_in,
00118 control_msgs::FollowJointTrajectoryFeedback* control_state,
00119 sensor_msgs::JointState* sensor_state, int robot_id);
00120
00121 private:
00122
00123 static bool JointDataToVector(const industrial::joint_data::JointData &joints,
00124 std::vector<double> &vec, int len);
00125
00126
00131 industrial::shared_types::shared_int valid_fields_from_message_;
00132
00139 bool convert_message(JointFeedbackExMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00140 };
00141
00142 }
00143 }
00144
00145 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_EX_RELAY_HANDLER_H