joint_trajectory_interface.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Southwest Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the Southwest Research Institute, nor the names
16  * of its contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_INTERFACE_H
33 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_INTERFACE_H
34 
35 #include <algorithm>
36 #include <vector>
37 #include <string>
38 #include <map>
39 #include "ros/ros.h"
40 #include "industrial_msgs/CmdJointTrajectory.h"
41 #include "motoman_msgs/CmdJointTrajectoryEx.h"
42 #include "industrial_msgs/StopMotion.h"
43 #include "sensor_msgs/JointState.h"
48 #include "trajectory_msgs/JointTrajectory.h"
50 
52 {
53 namespace joint_trajectory_interface
54 {
55 
61 
68 class JointTrajectoryInterface
69 {
70 public:
75  typedef std::map<int, RobotGroup>::iterator it_type;
76 
87  virtual bool init(std::string default_ip = "", int default_port = StandardSocketPorts::MOTION,
88  bool version_0 = false);
89 
97  virtual bool init(SmplMsgConnection* connection);
98 
111  virtual bool init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
112  const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
113 
126  virtual bool init(SmplMsgConnection* connection, const std::map<int, RobotGroup> &robot_groups,
127  const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
128 
129  virtual ~JointTrajectoryInterface();
130 
134  virtual void run()
135  {
136  ros::spin();
137  }
138 
139 protected:
143  virtual void trajectoryStop();
144 
154  virtual bool trajectory_to_msgs(const motoman_msgs::DynamicJointTrajectoryConstPtr& traj,
155  std::vector<SimpleMessage>* msgs);
156 
166  virtual bool trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr& traj,
167  std::vector<SimpleMessage>* msgs);
168 
178  virtual bool transform(const trajectory_msgs::JointTrajectoryPoint& pt_in,
179  trajectory_msgs::JointTrajectoryPoint* pt_out)
180  {
181  *pt_out = pt_in; // by default, no transform is applied
182  return true;
183  }
184 
185  virtual bool transform(const motoman_msgs::DynamicJointsGroup& pt_in, motoman_msgs::DynamicJointsGroup* pt_out)
186  {
187  *pt_out = pt_in; // by default, no transform is applied
188  return true;
189  }
190 
201  virtual bool select(const std::vector<std::string>& ros_joint_names, const motoman_msgs::DynamicJointsGroup& ros_pt,
202  const std::vector<std::string>& rbt_joint_names, motoman_msgs::DynamicJointsGroup* rbt_pt);
203 
204 
215  virtual bool select(const std::vector<std::string>& ros_joint_names,
216  const trajectory_msgs::JointTrajectoryPoint& ros_pt,
217  const std::vector<std::string>& rbt_joint_names, trajectory_msgs::JointTrajectoryPoint* rbt_pt);
218 
228  virtual bool create_message(int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage* msg);
229 
230  virtual bool create_message(int seq, const motoman_msgs::DynamicJointsGroup &pt, SimpleMessage* msg);
231 
232  virtual bool create_message_ex(int seq, const motoman_msgs::DynamicJointPoint &pt, SimpleMessage* msg);
233 
243  virtual bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity);
244 
254  virtual bool calc_velocity(const motoman_msgs::DynamicJointsGroup& pt, double* rbt_velocity);
255 
265  virtual bool calc_duration(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_duration);
266 
276  virtual bool calc_duration(const motoman_msgs::DynamicJointsGroup& pt, double* rbt_duration);
277 
286  virtual bool send_to_robot(const std::vector<SimpleMessage>& messages) = 0;
287 
294  virtual void jointTrajectoryExCB(const motoman_msgs::DynamicJointTrajectoryConstPtr &msg);
295 
302  virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
303 
312  virtual bool stopMotionCB(industrial_msgs::StopMotion::Request &req,
313  industrial_msgs::StopMotion::Response &res);
314 
321  virtual bool is_valid(const motoman_msgs::DynamicJointTrajectory &traj);
322 
329  virtual bool is_valid(const trajectory_msgs::JointTrajectory &traj);
330 
331  /*
332  * \brief Callback for JointState topic
333  *
334  * \param msg JointState message
335  */
336  virtual void jointStateCB(const sensor_msgs::JointStateConstPtr &msg);
337 
338  virtual void jointStateCB(const sensor_msgs::JointStateConstPtr &msg, int robot_id);
339 
340  TcpClient default_tcp_connection_;
341 
343  SmplMsgConnection* connection_;
344  ros::Subscriber sub_cur_pos_; // handle for joint-state topic subscription
345  ros::Subscriber sub_joint_trajectory_; // handle for joint-trajectory topic subscription
346  ros::ServiceServer srv_joint_trajectory_; // handle for joint-trajectory service
347  ros::Subscriber sub_joint_trajectory_ex_; // handle for joint-trajectory topic subscription
348  ros::ServiceServer srv_joint_trajectory_ex_; // handle for joint-trajectory service
349  ros::ServiceServer srv_stop_motion_; // handle for stop_motion service
350 
351  std::map<int, ros::ServiceServer> srv_stops_;
352  std::map<int, ros::ServiceServer> srv_joints_;
353  std::map<int, ros::Subscriber> sub_joint_trajectories_;
354  std::map<int, ros::Subscriber> sub_cur_positions_;
355 
356  std::vector<std::string> all_joint_names_;
357  std::map<int, RobotGroup> robot_groups_;
358  bool version_0_;
359  double default_joint_pos_; // default position to use for "dummy joints", if none specified
360  double default_vel_ratio_; // default velocity ratio to use for joint commands, if no velocity or max_vel specified
361  double default_duration_; // default duration to use for joint commands, if no
362  std::map<std::string, double> joint_vel_limits_; // cache of max joint velocities from URDF
363  sensor_msgs::JointState cur_joint_pos_; // cache of last received joint state
364 
365  std::map<int, sensor_msgs::JointState> cur_joint_pos_map_;
366 
367 private:
376  bool jointTrajectoryCB(industrial_msgs::CmdJointTrajectory::Request &req,
377  industrial_msgs::CmdJointTrajectory::Response &res);
378 
379 
380  bool jointTrajectoryExCB(motoman_msgs::CmdJointTrajectoryEx::Request &req,
381  motoman_msgs::CmdJointTrajectoryEx::Response &res);
382 };
383 
384 } // namespace joint_trajectory_interface
385 } // namespace industrial_robot_client
386 
387 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_INTERFACE_H
virtual bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity)
virtual bool transform(const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out)
virtual bool calc_duration(const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_duration)
virtual bool send_to_robot(const std::vector< JointTrajPtMessage > &messages)=0
ROSCPP_DECL void spin(Spinner &spinner)
static JointTrajPtMessage create_message(int seq, std::vector< double > joint_pos, double velocity, double duration)
virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)
virtual bool init(std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
virtual bool select(const std::vector< std::string > &ros_joint_names, const trajectory_msgs::JointTrajectoryPoint &ros_pt, const std::vector< std::string > &rbt_joint_names, trajectory_msgs::JointTrajectoryPoint *rbt_pt)
virtual bool stopMotionCB(industrial_msgs::StopMotion::Request &req, industrial_msgs::StopMotion::Response &res)
virtual bool trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector< JointTrajPtMessage > *msgs)


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute), Ted Miller (MotoROS) (Yaskawa Motoman), Eric Marcil (MotoROS) (Yaskawa Motoman)
autogenerated on Sat May 8 2021 02:27:43