joint_trajectory_action.cpp
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 #include <industrial_robot_client/joint_trajectory_action.h>
00033 #include <industrial_robot_client/utils.h>
00034 #include <industrial_utils/param_utils.h>
00035 #include <industrial_utils/utils.h>
00036 
00037 namespace industrial_robot_client
00038 {
00039 namespace joint_trajectory_action
00040 {
00041 JointTrajectoryAction::JointTrajectoryAction() :
00042     action_server_(node_, "joint_trajectory_action", boost::bind(&JointTrajectoryAction::goalCB, this, _1),
00043                    boost::bind(&JointTrajectoryAction::cancelCB, this, _1), false), has_active_goal_(false)
00044 {
00045   ros::NodeHandle pn("~");
00046 
00047   pn.param("constraints/goal_threshold", goal_threshold_, DEFAULT_GOAL_THRESHOLD_);
00048 
00049   if (!industrial_utils::param::getJointNames("controller_joint_names", joint_names_))
00050   {
00051     ROS_WARN("Unable to read 'controller_joint_names' param.  Using standard 6-DOF joint names.");
00052   }
00053   ROS_INFO_STREAM("Loaded " << joint_names_.size() << " joint names from 'controller_joint_names' parameter");
00054 
00055   // The controller joint names parameter includes empty joint names for those joints not supported
00056   // by the controller.  These are removed since the trajectory action should ignore these.
00057   std::remove(joint_names_.begin(), joint_names_.end(), std::string());
00058   ROS_INFO_STREAM("Filtered joint names to " << joint_names_.size() << " joints");
00059 
00060   pub_trajectory_command_ = node_.advertise<trajectory_msgs::JointTrajectory>("joint_path_command", 1);
00061   sub_trajectory_state_ = node_.subscribe("feedback_states", 1, &JointTrajectoryAction::controllerStateCB, this);
00062   sub_robot_status_ = node_.subscribe("robot_status", 1, &JointTrajectoryAction::robotStatusCB, this);
00063 
00064   watchdog_timer_ = node_.createTimer(ros::Duration(WATCHD0G_PERIOD_), &JointTrajectoryAction::watchdog, this);
00065   action_server_.start();
00066 }
00067 
00068 JointTrajectoryAction::~JointTrajectoryAction()
00069 {
00070 }
00071 
00072 void JointTrajectoryAction::robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg)
00073 {
00074   last_robot_status_ = msg; //caching robot status for later use.
00075 }
00076 
00077 void JointTrajectoryAction::watchdog(const ros::TimerEvent &e)
00078 {
00079   // Some debug logging
00080   if (!last_trajectory_state_)
00081   {
00082     ROS_DEBUG("Waiting for subscription to joint trajectory state");
00083   }
00084   if (!trajectory_state_recvd_)
00085   {
00086     ROS_DEBUG("Trajectory state not received since last watchdog");
00087   }
00088 
00089   // Aborts the active goal if the controller does not appear to be active.
00090   if (has_active_goal_)
00091   {
00092     if (!trajectory_state_recvd_)
00093     {
00094       // last_trajectory_state_ is null if the subscriber never makes a connection
00095       if (!last_trajectory_state_)
00096       {
00097         ROS_WARN("Aborting goal because we have never heard a controller state message.");
00098       }
00099       else
00100       {
00101         ROS_WARN_STREAM(
00102             "Aborting goal because we haven't heard from the controller in " << WATCHD0G_PERIOD_ << " seconds");
00103       }
00104 
00105       abortGoal();
00106 
00107     }
00108   }
00109 
00110   // Reset the trajectory state received flag
00111   trajectory_state_recvd_ = false;
00112 }
00113 
00114 void JointTrajectoryAction::goalCB(JointTractoryActionServer::GoalHandle & gh)
00115 {
00116   ROS_INFO("Received new goal");
00117 
00118   if (!gh.getGoal()->trajectory.points.empty())
00119   {
00120     if (industrial_utils::isSimilar(joint_names_, gh.getGoal()->trajectory.joint_names))
00121     {
00122 
00123       // Cancels the currently active goal.
00124       if (has_active_goal_)
00125       {
00126         ROS_WARN("Received new goal, canceling current goal");
00127         abortGoal();
00128       }
00129 
00130       // Sends the trajectory along to the controller
00131       if (withinGoalConstraints(last_trajectory_state_, gh.getGoal()->trajectory))
00132       {
00133 
00134         ROS_INFO_STREAM("Already within goal constraints, setting goal succeeded");
00135         gh.setAccepted();
00136         gh.setSucceeded();
00137         has_active_goal_ = false;
00138 
00139       }
00140       else
00141       {
00142         gh.setAccepted();
00143         active_goal_ = gh;
00144         has_active_goal_ = true;
00145 
00146         ROS_INFO("Publishing trajectory");
00147 
00148         current_traj_ = active_goal_.getGoal()->trajectory;
00149         pub_trajectory_command_.publish(current_traj_);
00150       }
00151     }
00152     else
00153     {
00154       ROS_ERROR("Joint trajectory action failing on invalid joints");
00155       control_msgs::FollowJointTrajectoryResult rslt;
00156       rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00157       gh.setRejected(rslt, "Joint names do not match");
00158     }
00159   }
00160   else
00161   {
00162     ROS_ERROR("Joint trajectory action failed on empty trajectory");
00163     control_msgs::FollowJointTrajectoryResult rslt;
00164     rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
00165     gh.setRejected(rslt, "Empty trajectory");
00166   }
00167 
00168   // Adding some informational log messages to indicate unsupported goal constraints
00169   if (gh.getGoal()->goal_time_tolerance.toSec() > 0.0)
00170   {
00171     ROS_WARN_STREAM("Ignoring goal time tolerance in action goal, may be supported in the future");
00172   }
00173   if (!gh.getGoal()->goal_tolerance.empty())
00174   {
00175     ROS_WARN_STREAM(
00176         "Ignoring goal tolerance in action, using paramater tolerance of " << goal_threshold_ << " instead");
00177   }
00178   if (!gh.getGoal()->path_tolerance.empty())
00179   {
00180     ROS_WARN_STREAM("Ignoring goal path tolerance, option not supported by ROS-Industrial drivers");
00181   }
00182 }
00183 
00184 void JointTrajectoryAction::cancelCB(JointTractoryActionServer::GoalHandle & gh)
00185 {
00186   ROS_DEBUG("Received action cancel request");
00187   if (active_goal_ == gh)
00188   {
00189     // Stops the controller.
00190     trajectory_msgs::JointTrajectory empty;
00191     empty.joint_names = joint_names_;
00192     pub_trajectory_command_.publish(empty);
00193 
00194     // Marks the current goal as canceled.
00195     active_goal_.setCanceled();
00196     has_active_goal_ = false;
00197   }
00198   else
00199   {
00200     ROS_WARN("Active goal and goal cancel do not match, ignoring cancel request");
00201   }
00202 }
00203 
00204 void JointTrajectoryAction::controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
00205 {
00206   //ROS_DEBUG("Checking controller state feedback");
00207   last_trajectory_state_ = msg;
00208   trajectory_state_recvd_ = true;
00209 
00210   if (!has_active_goal_)
00211   {
00212     //ROS_DEBUG("No active goal, ignoring feedback");
00213     return;
00214   }
00215   if (current_traj_.points.empty())
00216   {
00217     ROS_DEBUG("Current trajectory is empty, ignoring feedback");
00218     return;
00219   }
00220 
00221   if (!industrial_utils::isSimilar(joint_names_, msg->joint_names))
00222   {
00223     ROS_ERROR("Joint names from the controller don't match our joint names.");
00224     return;
00225   }
00226 
00227   // Checking for goal constraints
00228   // Checks that we have ended inside the goal constraints and has motion stopped
00229 
00230   ROS_DEBUG("Checking goal constraints");
00231   if (withinGoalConstraints(last_trajectory_state_, current_traj_))
00232   {
00233     if (last_robot_status_)
00234     {
00235       // Additional check for motion stoppage since the controller goal may still
00236       // be moving.  The current robot driver calls a motion stop if it receives
00237       // a new trajectory while it is still moving.  If the driver is not publishing
00238       // the motion state (i.e. old driver), this will still work, but it warns you.
00239       if (last_robot_status_->in_motion.val == industrial_msgs::TriState::FALSE)
00240       {
00241         ROS_INFO("Inside goal constraints, stopped moving, return success for action");
00242         active_goal_.setSucceeded();
00243         has_active_goal_ = false;
00244       }
00245       else if (last_robot_status_->in_motion.val == industrial_msgs::TriState::UNKNOWN)
00246       {
00247         ROS_INFO("Inside goal constraints, return success for action");
00248         ROS_WARN("Robot status in motion unknown, the robot driver node and controller code should be updated");
00249         active_goal_.setSucceeded();
00250         has_active_goal_ = false;
00251       }
00252       else
00253       {
00254         ROS_DEBUG("Within goal constraints but robot is still moving");
00255       }
00256     }
00257     else
00258     {
00259       ROS_INFO("Inside goal constraints, return success for action");
00260       ROS_WARN("Robot status is not being published the robot driver node and controller code should be updated");
00261       active_goal_.setSucceeded();
00262       has_active_goal_ = false;
00263     }
00264   }
00265 }
00266 
00267 void JointTrajectoryAction::abortGoal()
00268 {
00269   // Stops the controller.
00270   trajectory_msgs::JointTrajectory empty;
00271   pub_trajectory_command_.publish(empty);
00272 
00273   // Marks the current goal as aborted.
00274   active_goal_.setAborted();
00275   has_active_goal_ = false;
00276 }
00277 
00278 bool JointTrajectoryAction::withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00279                                                   const trajectory_msgs::JointTrajectory & traj)
00280 {
00281   bool rtn = false;
00282   if (traj.points.empty())
00283   {
00284     ROS_WARN("Empty joint trajectory passed to check goal constraints, return false");
00285     rtn = false;
00286   }
00287   else
00288   {
00289     int last_point = traj.points.size() - 1;
00290 
00291     if (industrial_robot_client::utils::isWithinRange(last_trajectory_state_->joint_names,
00292                                                       last_trajectory_state_->actual.positions, traj.joint_names,
00293                                                       traj.points[last_point].positions, goal_threshold_))
00294     {
00295       rtn = true;
00296     }
00297     else
00298     {
00299       rtn = false;
00300     }
00301   }
00302   return rtn;
00303 }
00304 
00305 } //joint_trajectory_action
00306 } //industrial_robot_client
00307 


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