joint_trajectory_action.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2012, 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_TRAJTORY_ACTION_H
00033 #define JOINT_TRAJTORY_ACTION_H
00034 
00035 #include <ros/ros.h>
00036 #include <actionlib/server/action_server.h>
00037 
00038 #include <trajectory_msgs/JointTrajectory.h>
00039 #include <control_msgs/FollowJointTrajectoryAction.h>
00040 #include <control_msgs/FollowJointTrajectoryFeedback.h>
00041 #include <industrial_msgs/RobotStatus.h>
00042 
00043 namespace industrial_robot_client
00044 {
00045 namespace joint_trajectory_action
00046 {
00047 
00048 class JointTrajectoryAction
00049 {
00050 
00051 public:
00056   JointTrajectoryAction();
00057 
00062   ~JointTrajectoryAction();
00063 
00067     void run() { ros::spin(); }
00068 
00069 private:
00070 
00071   typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> JointTractoryActionServer;
00072 
00076   ros::NodeHandle node_;
00077 
00081   JointTractoryActionServer action_server_;
00082 
00086   ros::Publisher pub_trajectory_command_;
00087 
00092   ros::Subscriber sub_trajectory_state_;
00093 
00098   ros::Subscriber sub_robot_status_;
00099 
00104   ros::Timer watchdog_timer_;
00105 
00109   bool controller_alive_;
00110 
00114   bool has_active_goal_;
00115 
00120   bool has_moved_once_;
00121 
00125   JointTractoryActionServer::GoalHandle active_goal_;
00129   trajectory_msgs::JointTrajectory current_traj_;
00130 
00135   static const double DEFAULT_GOAL_THRESHOLD_;// = 0.01;
00136 
00144   double goal_threshold_;
00145 
00151   std::vector<std::string> joint_names_;
00152 
00156   control_msgs::FollowJointTrajectoryFeedbackConstPtr last_trajectory_state_;
00157 
00161   industrial_msgs::RobotStatusConstPtr last_robot_status_;
00162 
00167   ros::Time time_to_check_;
00168 
00172   static const double WATCHDOG_PERIOD_;// = 1.0;
00173 
00180   void watchdog(const ros::TimerEvent &e);
00181 
00188   void goalCB(JointTractoryActionServer::GoalHandle gh);
00189 
00197   void cancelCB(JointTractoryActionServer::GoalHandle gh);
00205   void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg);
00206 
00214   void robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg);
00215 
00222   void abortGoal();
00223 
00234   bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00235                              const trajectory_msgs::JointTrajectory & traj);
00236 };
00237 
00238 } //joint_trajectory_action
00239 } //industrial_robot_client
00240 
00241 #endif /* JOINT_TRAJTORY_ACTION_H */


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Tue Jan 17 2017 21:10:11