joint_trajectory_interface.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2013, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *       * Redistributions of source code must retain the above copyright
00011  *       notice, this list of conditions and the following disclaimer.
00012  *       * Redistributions in binary form must reproduce the above copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *       * Neither the name of the Southwest Research Institute, nor the names
00016  *       of its contributors may be used to endorse or promote products derived
00017  *       from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_INTERFACE_H
00033 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_INTERFACE_H
00034 
00035 #include <algorithm>
00036 #include <vector>
00037 #include <string>
00038 #include <map>
00039 #include "ros/ros.h"
00040 #include "industrial_msgs/CmdJointTrajectory.h"
00041 #include "motoman_msgs/CmdJointTrajectoryEx.h"
00042 #include "industrial_msgs/StopMotion.h"
00043 #include "sensor_msgs/JointState.h"
00044 #include "simple_message/simple_message.h"
00045 #include "simple_message/smpl_msg_connection.h"
00046 #include "simple_message/socket/tcp_client.h"
00047 #include "simple_message/messages/joint_traj_pt_message.h"
00048 #include "trajectory_msgs/JointTrajectory.h"
00049 #include "motoman_driver/industrial_robot_client/robot_group.h"
00050 
00051 namespace industrial_robot_client
00052 {
00053 namespace joint_trajectory_interface
00054 {
00055 
00056 using industrial::smpl_msg_connection::SmplMsgConnection;
00057 using industrial::tcp_client::TcpClient;
00058 using industrial::joint_traj_pt_message::JointTrajPtMessage;
00059 using industrial::simple_message::SimpleMessage;
00060 namespace StandardSocketPorts = industrial::simple_socket::StandardSocketPorts;
00061 
00068 class JointTrajectoryInterface
00069 {
00070 
00071 public:
00072 
00076   JointTrajectoryInterface() : default_joint_pos_(0.0), default_vel_ratio_(0.1), default_duration_(10.0) {};
00077   typedef std::map<int, RobotGroup>::iterator it_type;
00078 
00089   virtual bool init(std::string default_ip = "", int default_port = StandardSocketPorts::MOTION, bool version_0 = false);
00090 
00098   virtual bool init(SmplMsgConnection* connection);
00099 
00112   virtual bool init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00113                     const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
00114 
00127   virtual bool init(SmplMsgConnection* connection, const std::map<int, RobotGroup> &robot_groups,
00128                     const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
00129 
00130   virtual ~JointTrajectoryInterface();
00131 
00135   virtual void run()
00136   {
00137     ros::spin();
00138   }
00139 
00140 protected:
00141 
00145   virtual void trajectoryStop();
00146 
00156   virtual bool trajectory_to_msgs(const motoman_msgs::DynamicJointTrajectoryConstPtr &traj, std::vector<SimpleMessage>* msgs);
00157 
00167   virtual bool trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector<SimpleMessage>* msgs);
00168 
00178   virtual bool transform(const trajectory_msgs::JointTrajectoryPoint& pt_in, trajectory_msgs::JointTrajectoryPoint* pt_out)
00179   {
00180     *pt_out = pt_in;  // by default, no transform is applied
00181     return true;
00182   }
00183 
00184   virtual bool transform(const motoman_msgs::DynamicJointsGroup& pt_in, motoman_msgs::DynamicJointsGroup* pt_out)
00185   {
00186     *pt_out = pt_in;  // by default, no transform is applied
00187     return true;
00188   }
00189 
00200   virtual bool select(const std::vector<std::string>& ros_joint_names, const motoman_msgs::DynamicJointsGroup& ros_pt,
00201                       const std::vector<std::string>& rbt_joint_names, motoman_msgs::DynamicJointsGroup* rbt_pt);
00202 
00203 
00214   virtual bool select(const std::vector<std::string>& ros_joint_names, const trajectory_msgs::JointTrajectoryPoint& ros_pt,
00215                       const std::vector<std::string>& rbt_joint_names, trajectory_msgs::JointTrajectoryPoint* rbt_pt);
00216 
00217 
00227   virtual bool create_message(int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage* msg);
00228 
00229   virtual bool create_message(int seq, const motoman_msgs::DynamicJointsGroup &pt, SimpleMessage* msg);
00230 
00231   virtual bool create_message_ex(int seq, const motoman_msgs::DynamicJointPoint &pt, SimpleMessage* msg);
00232 
00242   virtual bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity);
00243 
00253   virtual bool calc_velocity(const motoman_msgs::DynamicJointsGroup& pt, double* rbt_velocity);
00254 
00264   virtual bool calc_duration(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_duration);
00265 
00275   virtual bool calc_duration(const motoman_msgs::DynamicJointsGroup& pt, double* rbt_duration);
00276 
00285   virtual bool send_to_robot(const std::vector<SimpleMessage>& messages) = 0;
00286 
00293   virtual void jointTrajectoryExCB(const motoman_msgs::DynamicJointTrajectoryConstPtr &msg);
00294 
00301   virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
00302 
00311   virtual bool stopMotionCB(industrial_msgs::StopMotion::Request &req,
00312                             industrial_msgs::StopMotion::Response &res);
00313 
00320   virtual bool is_valid(const motoman_msgs::DynamicJointTrajectory &traj);
00321 
00328   virtual bool is_valid(const trajectory_msgs::JointTrajectory &traj);
00329 
00330   /*
00331    * \brief Callback for JointState topic
00332    *
00333    * \param msg JointState message
00334    */
00335   virtual void jointStateCB(const sensor_msgs::JointStateConstPtr &msg);
00336 
00337   virtual void jointStateCB(const sensor_msgs::JointStateConstPtr &msg, int robot_id);
00338 
00339   TcpClient default_tcp_connection_;
00340 
00341   ros::NodeHandle node_;
00342   SmplMsgConnection* connection_;
00343   ros::Subscriber sub_cur_pos_;  // handle for joint-state topic subscription
00344   ros::Subscriber sub_joint_trajectory_;  // handle for joint-trajectory topic subscription
00345   ros::ServiceServer srv_joint_trajectory_;  // handle for joint-trajectory service
00346   ros::Subscriber sub_joint_trajectory_ex_;  // handle for joint-trajectory topic subscription
00347   ros::ServiceServer srv_joint_trajectory_ex_;  // handle for joint-trajectory service
00348   ros::ServiceServer srv_stop_motion_;   // handle for stop_motion service
00349 
00350   std::map<int, ros::ServiceServer> srv_stops_;
00351   std::map<int, ros::ServiceServer> srv_joints_;
00352   std::map<int, ros::Subscriber> sub_joint_trajectories_;
00353   std::map<int, ros::Subscriber> sub_cur_positions_;
00354 
00355   std::vector<std::string> all_joint_names_;
00356   std::map<int, RobotGroup> robot_groups_;
00357   bool version_0_;
00358   double default_joint_pos_;  // default position to use for "dummy joints", if none specified
00359   double default_vel_ratio_;  // default velocity ratio to use for joint commands, if no velocity or max_vel specified
00360   double default_duration_;   // default duration to use for joint commands, if no
00361   std::map<std::string, double> joint_vel_limits_;  // cache of max joint velocities from URDF
00362   sensor_msgs::JointState cur_joint_pos_;  // cache of last received joint state
00363 
00364   std::map<int, sensor_msgs::JointState> cur_joint_pos_map_;
00365 
00366 private:
00375   bool jointTrajectoryCB(industrial_msgs::CmdJointTrajectory::Request &req,
00376                          industrial_msgs::CmdJointTrajectory::Response &res);
00377 
00378 
00379   bool jointTrajectoryExCB(motoman_msgs::CmdJointTrajectoryEx::Request &req,
00380                            motoman_msgs::CmdJointTrajectoryEx::Response &res);
00381 };
00382 
00383 }  // namespace joint_trajectory_interface
00384 } //industrial_robot_client
00385 
00386 #endif // MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_INTERFACE_H


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:57