Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
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 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_RELAY_HANDLER_H
00034 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_RELAY_HANDLER_H
00035
00036 #include <map>
00037 #include <string>
00038 #include <vector>
00039 #include "motoman_driver/industrial_robot_client/joint_relay_handler.h"
00040 #include "simple_message/messages/joint_feedback_message.h"
00041 #include "motoman_msgs/DynamicJointsGroup.h"
00042
00043 namespace industrial_robot_client
00044 {
00045 namespace joint_feedback_relay_handler
00046 {
00047
00048 using industrial::joint_feedback_message::JointFeedbackMessage;
00049 using industrial::simple_message::SimpleMessage;
00050 using industrial::smpl_msg_connection::SmplMsgConnection;
00051 using industrial_robot_client::joint_relay_handler::JointRelayHandler;
00052 using trajectory_msgs::JointTrajectoryPoint;
00053 using motoman_msgs::DynamicJointsGroup;
00054
00062 class JointFeedbackRelayHandler : public industrial_robot_client::joint_relay_handler::JointRelayHandler
00063 {
00064 public:
00068 JointFeedbackRelayHandler(int robot_id = -1) : robot_id_(robot_id) {};
00069
00070
00081 virtual bool init(SmplMsgConnection* connection,
00082 std::vector<std::string> &joint_names);
00083
00084 virtual bool init(SmplMsgConnection* connection,
00085 std::map<int, RobotGroup> &robot_groups);
00086
00087 protected:
00088 int robot_id_;
00089 bool version_0_;
00090
00091
00098 virtual bool convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state);
00099
00106 virtual bool convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00107
00108
00109 bool create_messages(SimpleMessage& msg_in,
00110 control_msgs::FollowJointTrajectoryFeedback* control_state,
00111 sensor_msgs::JointState* sensor_state);
00112
00113 bool create_messages(SimpleMessage& msg_in,
00114 control_msgs::FollowJointTrajectoryFeedback* control_state,
00115 sensor_msgs::JointState* sensor_state, int robot_id);
00116
00117
00118 virtual bool transform(const DynamicJointsGroup& state_in, DynamicJointsGroup* state_out)
00119 {
00120 *state_out = state_in;
00121 return true;
00122 }
00123
00124 virtual bool select(const DynamicJointsGroup& all_joint_state, const std::vector<std::string>& all_joint_names,
00125 DynamicJointsGroup* pub_joint_state, std::vector<std::string>* pub_joint_names);
00126
00127 private:
00128 static bool JointDataToVector(const industrial::joint_data::JointData &joints,
00129 std::vector<double> &vec, int len);
00130
00137 bool convert_message(JointFeedbackMessage& msg_in, JointTrajectoryPoint* joint_state);
00138
00145 bool convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id);
00146 };
00147
00148 }
00149 }
00150
00151
00152 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_FEEDBACK_RELAY_HANDLER_H