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 
00033 #include <ros/ros.h>
00034 #include <actionlib/server/action_server.h>
00035 
00036 #include <trajectory_msgs/JointTrajectory.h>
00037 #include <control_msgs/FollowJointTrajectoryAction.h>
00038 #include <control_msgs/FollowJointTrajectoryFeedback.h>
00039 
00040 const double DEFAULT_GOAL_THRESHOLD = 0.01;
00041 const std::string JOINT_TRAJECTORY_ACTION_PARAM_NAME = "joint_trajectory_action/joints";
00042 
00043 class JointTrajectoryExecuter
00044 {
00045 private:
00046   typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> JTAS;
00047   typedef JTAS::GoalHandle GoalHandle;
00048 public:
00049   JointTrajectoryExecuter(ros::NodeHandle &n) :
00050     node_(n),
00051     action_server_(node_, "joint_trajectory_action",
00052                    boost::bind(&JointTrajectoryExecuter::goalCB, this, _1),
00053                    boost::bind(&JointTrajectoryExecuter::cancelCB, this, _1),
00054                    false),
00055     has_active_goal_(false)
00056   {
00057     using namespace XmlRpc;
00058     ros::NodeHandle pn("~");
00059 
00060     fetchParameters(ros::this_node::getNamespace());
00061 
00062 
00063     pub_controller_command_ =
00064       node_.advertise<trajectory_msgs::JointTrajectory>("command", 1);
00065     sub_controller_state_ =
00066       node_.subscribe("feedback_states", 1, &JointTrajectoryExecuter::controllerStateCB, this);
00067 
00068     action_server_.start();
00069   }
00070 
00071   void fetchParameters(std::string nameSpace="")
00072   {
00073           XmlRpc::XmlRpcValue jointNames;
00074           ros::NodeHandle nh;
00075 
00076           if(nh.getParam(nameSpace + "/" + JOINT_TRAJECTORY_ACTION_PARAM_NAME,jointNames))
00077           {
00078                   if(jointNames.size() == 0)
00079                   {
00080                           ROS_ERROR_STREAM(ros::this_node::getName()<<
00081                                           ": Found 0 joints under parameter "<<JOINT_TRAJECTORY_ACTION_PARAM_NAME);
00082                           ros::shutdown();
00083                   }
00084           }
00085           else
00086           {
00087                   ROS_ERROR_STREAM(ros::this_node::getName()<<
00088                                   ": Could not find joint definitions under parameter "<<JOINT_TRAJECTORY_ACTION_PARAM_NAME);
00089                   ros::shutdown();
00090           }
00091 
00092           joint_names_.clear();
00093           for(int i = 0; i < jointNames.size(); i++)
00094           {
00095                   std::string name = static_cast<std::string>(jointNames[i]);
00096                   joint_names_.push_back(name);
00097           }
00098 
00099           // Gets the constraints for each joint.
00100           goal_constraints_.clear();
00101           for (size_t i = 0; i < joint_names_.size(); ++i)
00102           {
00103                 std::string ns = std::string("constraints/") + joint_names_[i];
00104                 double g, t;
00105                 nh.param(ns + "/goal", g, DEFAULT_GOAL_THRESHOLD);
00106                 nh.param(ns + "/trajectory", t, -1.0);
00107                 goal_constraints_[joint_names_[i]] = g;
00108                 trajectory_constraints_[joint_names_[i]] = t;
00109           }
00110 
00111           nh.param("constraints/stopped_velocity_tolerance", stopped_velocity_tolerance_, 0.01);
00112 
00113   }
00114 
00115   ~JointTrajectoryExecuter()
00116   {
00117    pub_controller_command_.shutdown();
00118     sub_controller_state_.shutdown();
00119     watchdog_timer_.stop();
00120   }
00121 
00122   bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00123                              const std::map<std::string, double>& constraints,
00124                              const trajectory_msgs::JointTrajectory& traj) {
00125     ROS_DEBUG("Checking goal contraints");
00126     int last = traj.points.size() - 1;
00127     for (size_t i = 0; i < msg->joint_names.size(); ++i)
00128     {
00129       double abs_error = fabs(msg->actual.positions[i]-traj.points[last].positions[i]);
00130       double goal_constraint = constraints.at(msg->joint_names[i]);
00131       if (goal_constraint >= 0 && abs_error > goal_constraint)
00132       {
00133         ROS_DEBUG("Bad constraint: %f, abs_errs: %f", goal_constraint, abs_error);
00134         return false;
00135       }
00136       ROS_DEBUG("Checking constraint: %f, abs_errs: %f", goal_constraint, abs_error);
00137     }
00138     return true;
00139   }
00140 
00141 private:
00142 
00143   static bool setsEqual(const std::vector<std::string> &a, const std::vector<std::string> &b)
00144   {
00145     if (a.size() != b.size())
00146       return false;
00147 
00148     for (size_t i = 0; i < a.size(); ++i)
00149     {
00150       if (count(b.begin(), b.end(), a[i]) != 1)
00151         return false;
00152     }
00153     for (size_t i = 0; i < b.size(); ++i)
00154     {
00155       if (count(a.begin(), a.end(), b[i]) != 1)
00156         return false;
00157     }
00158 
00159     return true;
00160   }
00161 
00162   void watchdog(const ros::TimerEvent &e)
00163   {
00164     ros::Time now = ros::Time::now();
00165 
00166     // Aborts the active goal if the controller does not appear to be active.
00167     if (has_active_goal_)
00168     {
00169       bool should_abort = false;
00170       if (!last_controller_state_)
00171       {
00172         should_abort = true;
00173         ROS_WARN("Aborting goal because we have never heard a controller state message.");
00174       }
00175       else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
00176       {
00177         should_abort = true;
00178         ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
00179                  (now - last_controller_state_->header.stamp).toSec());
00180       }
00181 
00182       if (should_abort)
00183       {
00184         // Stops the controller.
00185         trajectory_msgs::JointTrajectory empty;
00186         empty.joint_names = joint_names_;
00187         pub_controller_command_.publish(empty);
00188 
00189         // Marks the current goal as aborted.
00190         active_goal_.setAborted();
00191         has_active_goal_ = false;
00192       }
00193     }
00194   }
00195 
00196   void goalCB(GoalHandle gh)
00197   {
00198     // Ensures that the joints in the goal match the joints we are commanding.
00199     ROS_DEBUG("Received goal: goalCB");
00200     if (!setsEqual(joint_names_, gh.getGoal()->trajectory.joint_names))
00201     {
00202       ROS_ERROR("Joints on incoming goal don't match our joints");
00203       gh.setRejected();
00204       return;
00205     }
00206 
00207     // Cancels the currently active goal.
00208     if (has_active_goal_)
00209     {
00210       ROS_DEBUG("Received new goal, canceling current goal");
00211       // Stops the controller.
00212       trajectory_msgs::JointTrajectory empty;
00213       empty.joint_names = joint_names_;
00214       pub_controller_command_.publish(empty);
00215 
00216       // Marks the current goal as canceled.
00217       active_goal_.setCanceled();
00218       has_active_goal_ = false;
00219     }
00220 
00221     // Sends the trajectory along to the controller
00222     if(withinGoalConstraints(last_controller_state_,
00223                              goal_constraints_,
00224                              gh.getGoal()->trajectory)) {
00225       ROS_INFO_STREAM("Already within goal constraints");
00226       gh.setAccepted();
00227       gh.setSucceeded();
00228     } else {
00229       gh.setAccepted();
00230       active_goal_ = gh;
00231       has_active_goal_ = true;
00232 
00233       ROS_INFO("Publishing trajectory");
00234 
00235       current_traj_ = active_goal_.getGoal()->trajectory;
00236       pub_controller_command_.publish(current_traj_);
00237     }
00238   }
00239 
00240   void cancelCB(GoalHandle gh)
00241   {
00242     ROS_DEBUG("Received action cancel request");
00243     if (active_goal_ == gh)
00244     {
00245       // Stops the controller.
00246       trajectory_msgs::JointTrajectory empty;
00247       empty.joint_names = joint_names_;
00248       pub_controller_command_.publish(empty);
00249 
00250       // Marks the current goal as canceled.
00251       active_goal_.setCanceled();
00252       has_active_goal_ = false;
00253     }
00254   }
00255 
00256 
00257   ros::NodeHandle node_;
00258   JTAS action_server_;
00259   ros::Publisher pub_controller_command_;
00260   ros::Subscriber sub_controller_state_;
00261   ros::Timer watchdog_timer_;
00262 
00263   bool has_active_goal_;
00264   GoalHandle active_goal_;
00265   trajectory_msgs::JointTrajectory current_traj_;
00266 
00267 
00268   std::vector<std::string> joint_names_;
00269   std::map<std::string,double> goal_constraints_;
00270   std::map<std::string,double> trajectory_constraints_;
00271   double goal_time_constraint_;
00272   double stopped_velocity_tolerance_;
00273 
00274   control_msgs::FollowJointTrajectoryFeedbackConstPtr last_controller_state_;
00275 
00276   void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
00277   {
00278     //ROS_DEBUG("Checking controller state feedback");
00279     last_controller_state_ = msg;
00280     ros::Time now = ros::Time::now();
00281 
00282     if (!has_active_goal_)
00283     {
00284       //ROS_DEBUG("No active goal, ignoring feedback");
00285       return;
00286     }
00287     if (current_traj_.points.empty())
00288     {
00289       ROS_DEBUG("Current trajecotry is empty, ignoring feedback");
00290       return;
00291     }
00292     /* NOT CONCERNED ABOUT TRAJECTORY TIMING AT THIS POINT
00293     if (now < current_traj_.header.stamp + current_traj_.points[0].time_from_start)
00294       return;
00295     */
00296 
00297     if (!setsEqual(joint_names_, msg->joint_names))
00298     {
00299       ROS_ERROR("Joint names from the controller don't match our joint names.");
00300       return;
00301     }
00302 
00303     // Checking for goal constraints
00304     // Checks that we have ended inside the goal constraints
00305 
00306     ROS_DEBUG("Checking goal contraints");
00307     if(withinGoalConstraints(msg,
00308                              goal_constraints_,
00309                              current_traj_)) {
00310       ROS_INFO("Inside goal contraints, return success for action");
00311       active_goal_.setSucceeded();
00312       has_active_goal_ = false;
00313     }
00314     // Verifies that the controller has stayed within the trajectory constraints.
00315     /*  DISABLING THIS MORE COMPLICATED GOAL CHECKING AND ERROR DETECTION
00316 
00317 
00318     int last = current_traj_.points.size() - 1;
00319     ros::Time end_time = current_traj_.header.stamp + current_traj_.points[last].time_from_start;
00320     if (now < end_time)
00321     {
00322       // Checks that the controller is inside the trajectory constraints.
00323       for (size_t i = 0; i < msg->joint_names.size(); ++i)
00324       {
00325         double abs_error = fabs(msg->error.positions[i]);
00326         double constraint = trajectory_constraints_[msg->joint_names[i]];
00327         if (constraint >= 0 && abs_error > constraint)
00328         {
00329           // Stops the controller.
00330           trajectory_msgs::JointTrajectory empty;
00331           empty.joint_names = joint_names_;
00332           pub_controller_command_.publish(empty);
00333 
00334           active_goal_.setAborted();
00335           has_active_goal_ = false;
00336           ROS_WARN("Aborting because we would up outside the trajectory constraints");
00337           return;
00338         }
00339       }
00340     }
00341     else
00342     {
00343       // Checks that we have ended inside the goal constraints
00344       bool inside_goal_constraints = true;
00345       for (size_t i = 0; i < msg->joint_names.size() && inside_goal_constraints; ++i)
00346       {
00347         double abs_error = fabs(msg->error.positions[i]);
00348         double goal_constraint = goal_constraints_[msg->joint_names[i]];
00349         if (goal_constraint >= 0 && abs_error > goal_constraint)
00350           inside_goal_constraints = false;
00351 
00352         // It's important to be stopped if that's desired.
00353         if (fabs(msg->desired.velocities[i]) < 1e-6)
00354         {
00355           if (fabs(msg->actual.velocities[i]) > stopped_velocity_tolerance_)
00356             inside_goal_constraints = false;
00357         }
00358       }
00359 
00360       if (inside_goal_constraints)
00361       {
00362         active_goal_.setSucceeded();
00363         has_active_goal_ = false;
00364       }
00365       else if (now < end_time + ros::Duration(goal_time_constraint_))
00366       {
00367         // Still have some time left to make it.
00368       }
00369       else
00370       {
00371         ROS_WARN("Aborting because we wound up outside the goal constraints");
00372         active_goal_.setAborted();
00373         has_active_goal_ = false;
00374       }
00375 
00376     }
00377     */
00378   }
00379 };
00380 
00381 
00382 int main(int argc, char** argv)
00383 {
00384   ros::init(argc, argv, "joint_trajectory_action_node");
00385   ros::NodeHandle node;//("~");
00386   JointTrajectoryExecuter jte(node);
00387 
00388   ros::spin();
00389 
00390   return 0;
00391 }
00392 
00393 
00394 
00395 


object_manipulation_tools
Author(s): Jnicho
autogenerated on Mon Oct 6 2014 00:56:17