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 #ifndef MOTOMAN_DRIVER_JOINT_TRAJECTORY_STREAMER_H
00033 #define MOTOMAN_DRIVER_JOINT_TRAJECTORY_STREAMER_H
00034
00035 #include <map>
00036 #include <string>
00037 #include <vector>
00038 #include "motoman_driver/motion_ctrl.h"
00039 #include "motoman_driver/industrial_robot_client/joint_trajectory_streamer.h"
00040 #include "simple_message/joint_data.h"
00041 #include "simple_message/simple_message.h"
00042 #include "std_srvs/Trigger.h"
00043
00044 namespace motoman
00045 {
00046 namespace joint_trajectory_streamer
00047 {
00048
00049 using motoman::motion_ctrl::MotomanMotionCtrl;
00050 using industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer;
00051 using industrial::simple_message::SimpleMessage;
00052 using industrial::smpl_msg_connection::SmplMsgConnection;
00053
00059
00065 class MotomanJointTrajectoryStreamer : public JointTrajectoryStreamer
00066 {
00067 public:
00068
00069
00070 using JointTrajectoryStreamer::init;
00071 using JointTrajectoryInterface::is_valid;
00072
00078 MotomanJointTrajectoryStreamer(int robot_id = -1) : JointTrajectoryStreamer(1),
00079 robot_id_(robot_id) {}
00080
00081 ~MotomanJointTrajectoryStreamer();
00082
00095 virtual bool init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00096 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
00097
00110 virtual bool init(SmplMsgConnection* connection, const std::map<int, RobotGroup> &robot_groups,
00111 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
00112
00122 virtual bool create_message(int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage* msg);
00123
00124 virtual bool create_message(int seq, const motoman_msgs::DynamicJointsGroup &pt, SimpleMessage* msg);
00125
00126 virtual bool create_message_ex(int seq, const motoman_msgs::DynamicJointPoint &point, SimpleMessage* msg);
00127
00128 virtual bool send_to_robot(const std::vector<SimpleMessage>& messages);
00129
00130 virtual void streamingThread();
00131
00132 protected:
00133
00134 int robot_id_;
00135 MotomanMotionCtrl motion_ctrl_;
00136
00137 std::map<int, MotomanMotionCtrl> motion_ctrl_map_;
00138
00139 void trajectoryStop();
00140 bool is_valid(const trajectory_msgs::JointTrajectory &traj);
00141 bool is_valid(const motoman_msgs::DynamicJointTrajectory &traj);
00142
00143 static bool VectorToJointData(const std::vector<double> &vec,
00144 industrial::joint_data::JointData &joints);
00145
00150 ros::ServiceServer disabler_;
00151
00156 ros::ServiceServer enabler_;
00157
00163 bool disableRobotCB(std_srvs::Trigger::Request &req,
00164 std_srvs::Trigger::Response &res);
00165
00171 bool enableRobotCB(std_srvs::Trigger::Request &req,
00172 std_srvs::Trigger::Response &res);
00173
00174
00175 };
00176
00177 }
00178 }
00179
00180 #endif // MOTOMAN_DRIVER_JOINT_TRAJECTORY_STREAMER_H