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 JOINT_TRAJECTORY_INTERFACE_H
00033 #define JOINT_TRAJECTORY_INTERFACE_H
00034
00035 #include <map>
00036 #include <vector>
00037 #include <string>
00038
00039 #include "ros/ros.h"
00040 #include "industrial_msgs/CmdJointTrajectory.h"
00041 #include "industrial_msgs/StopMotion.h"
00042 #include "sensor_msgs/JointState.h"
00043 #include "simple_message/simple_message.h"
00044 #include "simple_message/smpl_msg_connection.h"
00045 #include "simple_message/socket/tcp_client.h"
00046 #include "simple_message/messages/joint_traj_pt_message.h"
00047 #include "trajectory_msgs/JointTrajectory.h"
00048
00049 namespace industrial_robot_client
00050 {
00051 namespace joint_trajectory_interface
00052 {
00053
00054 using industrial::smpl_msg_connection::SmplMsgConnection;
00055 using industrial::tcp_client::TcpClient;
00056 using industrial::joint_traj_pt_message::JointTrajPtMessage;
00057 using industrial::simple_message::SimpleMessage;
00058 namespace StandardSocketPorts = industrial::simple_socket::StandardSocketPorts;
00059
00066 class JointTrajectoryInterface
00067 {
00068
00069 public:
00070
00074 JointTrajectoryInterface() : default_joint_pos_(0.0), default_vel_ratio_(0.1), default_duration_(10.0) {};
00075
00086 virtual bool init(std::string default_ip = "", int default_port = StandardSocketPorts::MOTION);
00087
00095 virtual bool init(SmplMsgConnection* connection);
00096
00109 virtual bool init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00110 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
00111
00112 virtual ~JointTrajectoryInterface();
00113
00117 virtual void run() { ros::spin(); }
00118
00119 protected:
00120
00124 virtual void trajectoryStop();
00125
00135 virtual bool trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector<SimpleMessage>* msgs);
00136
00146 virtual bool transform(const trajectory_msgs::JointTrajectoryPoint& pt_in, trajectory_msgs::JointTrajectoryPoint* pt_out)
00147 {
00148 *pt_out = pt_in;
00149 return true;
00150 }
00151
00162 virtual bool select(const std::vector<std::string>& ros_joint_names, const trajectory_msgs::JointTrajectoryPoint& ros_pt,
00163 const std::vector<std::string>& rbt_joint_names, trajectory_msgs::JointTrajectoryPoint* rbt_pt);
00164
00174 virtual bool create_message(int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage* msg);
00175
00185 virtual bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity);
00186
00196 virtual bool calc_duration(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_duration);
00197
00206 virtual bool send_to_robot(const std::vector<SimpleMessage>& messages)=0;
00207
00214 virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
00215
00224 virtual bool stopMotionCB(industrial_msgs::StopMotion::Request &req,
00225 industrial_msgs::StopMotion::Response &res);
00226
00233 virtual bool is_valid(const trajectory_msgs::JointTrajectory &traj);
00234
00235
00236
00237
00238
00239
00240 virtual void jointStateCB(const sensor_msgs::JointStateConstPtr &msg);
00241
00242 TcpClient default_tcp_connection_;
00243
00244 ros::NodeHandle node_;
00245 SmplMsgConnection* connection_;
00246 ros::Subscriber sub_cur_pos_;
00247 ros::Subscriber sub_joint_trajectory_;
00248 ros::ServiceServer srv_joint_trajectory_;
00249 ros::ServiceServer srv_stop_motion_;
00250 std::vector<std::string> all_joint_names_;
00251 double default_joint_pos_;
00252 double default_vel_ratio_;
00253 double default_duration_;
00254 std::map<std::string, double> joint_vel_limits_;
00255 sensor_msgs::JointState cur_joint_pos_;
00256
00257 private:
00266 bool jointTrajectoryCB(industrial_msgs::CmdJointTrajectory::Request &req,
00267 industrial_msgs::CmdJointTrajectory::Response &res);
00268 };
00269
00270 }
00271 }
00272
00273 #endif