joint_trajectory_interface.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, 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 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 "simple_message/smpl_msg_connection.h"
00043 #include "simple_message/socket/tcp_client.h"
00044 #include "simple_message/messages/joint_traj_pt_message.h"
00045 #include "trajectory_msgs/JointTrajectory.h"
00046 
00047 namespace industrial_robot_client
00048 {
00049 namespace joint_trajectory_interface
00050 {
00051 
00052   using industrial::smpl_msg_connection::SmplMsgConnection;
00053   using industrial::tcp_client::TcpClient;
00054   using industrial::joint_traj_pt_message::JointTrajPtMessage;
00055 
00062 class JointTrajectoryInterface
00063 {
00064 
00065 public:
00066 
00070     JointTrajectoryInterface() : default_joint_pos_(0.0), default_vel_ratio_(0.1), default_duration_(10.0) {};
00071 
00077     virtual bool init();
00078 
00086     virtual bool init(SmplMsgConnection* connection);
00087 
00100   virtual bool init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00101                     const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
00102 
00103   virtual ~JointTrajectoryInterface();
00104 
00108   virtual void run() { ros::spin(); }
00109 
00110 protected:
00111 
00115   virtual void trajectoryStop();
00116 
00126   virtual bool trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector<JointTrajPtMessage>* msgs);
00127 
00137   virtual bool transform(const trajectory_msgs::JointTrajectoryPoint& pt_in, trajectory_msgs::JointTrajectoryPoint* pt_out)
00138   {
00139     *pt_out = pt_in;  // by default, no transform is applied
00140     return true;
00141   }
00142 
00153   virtual bool select(const std::vector<std::string>& ros_joint_names, const trajectory_msgs::JointTrajectoryPoint& ros_pt,
00154                       const std::vector<std::string>& rbt_joint_names, trajectory_msgs::JointTrajectoryPoint* rbt_pt);
00155 
00167   virtual bool calc_speed(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity, double* rbt_duration);
00168 
00178   virtual bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity);
00179 
00189   virtual bool calc_duration(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_duration);
00190 
00199   virtual bool send_to_robot(const std::vector<JointTrajPtMessage>& messages)=0;
00200 
00207   virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
00208 
00217   virtual bool stopMotionCB(industrial_msgs::StopMotion::Request &req,
00218                                     industrial_msgs::StopMotion::Response &res);
00219 
00220   TcpClient default_tcp_connection_;
00221 
00222   ros::NodeHandle node_;
00223   SmplMsgConnection* connection_;
00224   ros::Subscriber sub_joint_trajectory_; // handle for joint-trajectory topic subscription
00225   ros::ServiceServer srv_joint_trajectory_;  // handle for joint-trajectory service
00226   ros::ServiceServer srv_stop_motion_;   // handle for stop_motion service
00227   std::vector<std::string> all_joint_names_;
00228   double default_joint_pos_;  // default position to use for "dummy joints", if none specified
00229   double default_vel_ratio_;  // default velocity ratio to use for joint commands, if no velocity or max_vel specified
00230   double default_duration_;   // default duration to use for joint commands, if no
00231   std::map<std::string, double> joint_vel_limits_;  // cache of max joint velocities from URDF
00232 
00233 private:
00234   static JointTrajPtMessage create_message(int seq, std::vector<double> joint_pos, double velocity, double duration);
00235 
00244   bool jointTrajectoryCB(industrial_msgs::CmdJointTrajectory::Request &req,
00245                          industrial_msgs::CmdJointTrajectory::Response &res);
00246 };
00247 
00248 } //joint_trajectory_interface
00249 } //industrial_robot_client
00250 
00251 #endif /* JOINT_TRAJECTORY_INTERFACE_H */


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Mon Oct 6 2014 00:55:19