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/smpl_msg_connection.h"
00044 #include "simple_message/socket/tcp_client.h"
00045 #include "simple_message/messages/joint_traj_pt_message.h"
00046 #include "trajectory_msgs/JointTrajectory.h"
00047
00048 namespace industrial_robot_client
00049 {
00050 namespace joint_trajectory_interface
00051 {
00052
00053 using industrial::smpl_msg_connection::SmplMsgConnection;
00054 using industrial::tcp_client::TcpClient;
00055 using industrial::joint_traj_pt_message::JointTrajPtMessage;
00056 namespace StandardSocketPorts = industrial::simple_socket::StandardSocketPorts;
00057
00064 class JointTrajectoryInterface
00065 {
00066
00067 public:
00068
00072 JointTrajectoryInterface() : default_joint_pos_(0.0), default_vel_ratio_(0.1), default_duration_(10.0) {};
00073
00084 virtual bool init(std::string default_ip = "", int default_port = StandardSocketPorts::MOTION);
00085
00086
00094 virtual bool init(SmplMsgConnection* connection);
00095
00108 virtual bool init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00109 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
00110
00111 virtual ~JointTrajectoryInterface();
00112
00116 virtual void run() { ros::spin(); }
00117
00118 protected:
00119
00123 virtual void trajectoryStop();
00124
00134 virtual bool trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector<JointTrajPtMessage>* msgs);
00135
00145 virtual bool transform(const trajectory_msgs::JointTrajectoryPoint& pt_in, trajectory_msgs::JointTrajectoryPoint* pt_out)
00146 {
00147 *pt_out = pt_in;
00148 return true;
00149 }
00150
00161 virtual bool select(const std::vector<std::string>& ros_joint_names, const trajectory_msgs::JointTrajectoryPoint& ros_pt,
00162 const std::vector<std::string>& rbt_joint_names, trajectory_msgs::JointTrajectoryPoint* rbt_pt);
00163
00175 virtual bool calc_speed(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity, double* rbt_duration);
00176
00186 virtual bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity);
00187
00197 virtual bool calc_duration(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_duration);
00198
00207 virtual bool send_to_robot(const std::vector<JointTrajPtMessage>& messages)=0;
00208
00215 virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
00216
00225 virtual bool stopMotionCB(industrial_msgs::StopMotion::Request &req,
00226 industrial_msgs::StopMotion::Response &res);
00227
00234 virtual bool is_valid(const trajectory_msgs::JointTrajectory &traj);
00235
00236
00237
00238
00239
00240
00241 virtual void jointStateCB(const sensor_msgs::JointStateConstPtr &msg);
00242
00243 TcpClient default_tcp_connection_;
00244
00245 ros::NodeHandle node_;
00246 SmplMsgConnection* connection_;
00247 ros::Subscriber sub_cur_pos_;
00248 ros::Subscriber sub_joint_trajectory_;
00249 ros::ServiceServer srv_joint_trajectory_;
00250 ros::ServiceServer srv_stop_motion_;
00251 std::vector<std::string> all_joint_names_;
00252 double default_joint_pos_;
00253 double default_vel_ratio_;
00254 double default_duration_;
00255 std::map<std::string, double> joint_vel_limits_;
00256 sensor_msgs::JointState cur_joint_pos_;
00257
00258
00259 private:
00260 static JointTrajPtMessage create_message(int seq, std::vector<double> joint_pos, double velocity, double duration);
00261
00270 bool jointTrajectoryCB(industrial_msgs::CmdJointTrajectory::Request &req,
00271 industrial_msgs::CmdJointTrajectory::Response &res);
00272 };
00273
00274 }
00275 }
00276
00277 #endif