simple_action_client.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
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
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef ACTIONLIB__CLIENT__SIMPLE_ACTION_CLIENT_H_
00036 #define ACTIONLIB__CLIENT__SIMPLE_ACTION_CLIENT_H_
00037 
00038 #include <boost/thread/condition.hpp>
00039 #include <boost/thread/mutex.hpp>
00040 #include <boost/scoped_ptr.hpp>
00041 #include <boost/concept_check.hpp>
00042 
00043 #include <string>
00044 
00045 #include "ros/ros.h"
00046 #include "ros/callback_queue.h"
00047 #include "actionlib/client/action_client.h"
00048 #include "actionlib/client/simple_goal_state.h"
00049 #include "actionlib/client/simple_client_goal_state.h"
00050 #include "actionlib/client/terminal_state.h"
00051 
00052 #ifndef DEPRECATED
00053 #if defined(__GNUC__)
00054 #define DEPRECATED __attribute__((deprecated))
00055 #else
00056 #define DEPRECATED
00057 #endif
00058 #endif
00059 
00060 
00061 namespace actionlib
00062 {
00063 
00071 template<class ActionSpec>
00072 class SimpleActionClient
00073 {
00074 private:
00075   ACTION_DEFINITION(ActionSpec);
00076   typedef ClientGoalHandle<ActionSpec> GoalHandleT;
00077   typedef SimpleActionClient<ActionSpec> SimpleActionClientT;
00078 
00079 public:
00080   typedef boost::function<void (const SimpleClientGoalState & state,
00081     const ResultConstPtr & result)> SimpleDoneCallback;
00082   typedef boost::function<void ()> SimpleActiveCallback;
00083   typedef boost::function<void (const FeedbackConstPtr & feedback)> SimpleFeedbackCallback;
00084 
00093   SimpleActionClient(const std::string & name, bool spin_thread = true)
00094   : cur_simple_state_(SimpleGoalState::PENDING)
00095   {
00096     initSimpleClient(nh_, name, spin_thread);
00097   }
00098 
00109   SimpleActionClient(ros::NodeHandle & n, const std::string & name, bool spin_thread = true)
00110   : cur_simple_state_(SimpleGoalState::PENDING)
00111   {
00112     initSimpleClient(n, name, spin_thread);
00113   }
00114 
00115   ~SimpleActionClient();
00116 
00131   bool waitForServer(const ros::Duration & timeout = ros::Duration(0, 0) ) const
00132   {
00133     return ac_->waitForActionServerToStart(timeout);
00134   }
00135 
00140   bool isServerConnected() const
00141   {
00142     return ac_->isServerConnected();
00143   }
00144 
00154   void sendGoal(const Goal & goal,
00155     SimpleDoneCallback done_cb = SimpleDoneCallback(),
00156     SimpleActiveCallback active_cb = SimpleActiveCallback(),
00157     SimpleFeedbackCallback feedback_cb = SimpleFeedbackCallback());
00158 
00170   SimpleClientGoalState sendGoalAndWait(const Goal & goal,
00171     const ros::Duration & execute_timeout = ros::Duration(0, 0),
00172     const ros::Duration & preempt_timeout = ros::Duration(0, 0));
00173 
00179   bool waitForResult(const ros::Duration & timeout = ros::Duration(0, 0));
00180 
00185   ResultConstPtr getResult() const;
00186 
00193   SimpleClientGoalState getState() const;
00194 
00201   void cancelAllGoals();
00202 
00207   void cancelGoalsAtAndBeforeTime(const ros::Time & time);
00208 
00212   void cancelGoal();
00213 
00220   void stopTrackingGoal();
00221 
00222 private:
00223   typedef ActionClient<ActionSpec> ActionClientT;
00224   ros::NodeHandle nh_;
00225   GoalHandleT gh_;
00226 
00227   SimpleGoalState cur_simple_state_;
00228 
00229   // Signalling Stuff
00230   boost::condition done_condition_;
00231   boost::mutex done_mutex_;
00232 
00233   // User Callbacks
00234   SimpleDoneCallback done_cb_;
00235   SimpleActiveCallback active_cb_;
00236   SimpleFeedbackCallback feedback_cb_;
00237 
00238   // Spin Thread Stuff
00239   boost::mutex terminate_mutex_;
00240   bool need_to_terminate_;
00241   boost::thread * spin_thread_;
00242   ros::CallbackQueue callback_queue;
00243 
00244   boost::scoped_ptr<ActionClientT> ac_;  // Action client depends on callback_queue, so it must be destroyed before callback_queue
00245 
00246   // ***** Private Funcs *****
00247   void initSimpleClient(ros::NodeHandle & n, const std::string & name, bool spin_thread);
00248   void handleTransition(GoalHandleT gh);
00249   void handleFeedback(GoalHandleT gh, const FeedbackConstPtr & feedback);
00250   void setSimpleState(const SimpleGoalState::StateEnum & next_state);
00251   void setSimpleState(const SimpleGoalState & next_state);
00252   void spinThread();
00253 };
00254 
00255 
00256 template<class ActionSpec>
00257 void SimpleActionClient<ActionSpec>::initSimpleClient(ros::NodeHandle & n, const std::string & name,
00258   bool spin_thread)
00259 {
00260   if (spin_thread) {
00261     ROS_DEBUG_NAMED("actionlib", "Spinning up a thread for the SimpleActionClient");
00262     need_to_terminate_ = false;
00263     spin_thread_ =
00264       new boost::thread(boost::bind(&SimpleActionClient<ActionSpec>::spinThread, this));
00265     ac_.reset(new ActionClientT(n, name, &callback_queue));
00266   } else {
00267     spin_thread_ = NULL;
00268     ac_.reset(new ActionClientT(n, name));
00269   }
00270 }
00271 
00272 template<class ActionSpec>
00273 SimpleActionClient<ActionSpec>::~SimpleActionClient()
00274 {
00275   if (spin_thread_) {
00276     {
00277       boost::mutex::scoped_lock terminate_lock(terminate_mutex_);
00278       need_to_terminate_ = true;
00279     }
00280     spin_thread_->join();
00281     delete spin_thread_;
00282   }
00283   gh_.reset();
00284   ac_.reset();
00285 }
00286 
00287 template<class ActionSpec>
00288 void SimpleActionClient<ActionSpec>::spinThread()
00289 {
00290   while (nh_.ok()) {
00291     {
00292       boost::mutex::scoped_lock terminate_lock(terminate_mutex_);
00293       if (need_to_terminate_) {
00294         break;
00295       }
00296     }
00297     callback_queue.callAvailable(ros::WallDuration(0.1f));
00298   }
00299 }
00300 
00301 template<class ActionSpec>
00302 void SimpleActionClient<ActionSpec>::setSimpleState(const SimpleGoalState::StateEnum & next_state)
00303 {
00304   setSimpleState(SimpleGoalState(next_state) );
00305 }
00306 
00307 template<class ActionSpec>
00308 void SimpleActionClient<ActionSpec>::setSimpleState(const SimpleGoalState & next_state)
00309 {
00310   ROS_DEBUG_NAMED("actionlib", "Transitioning SimpleState from [%s] to [%s]",
00311     cur_simple_state_.toString().c_str(),
00312     next_state.toString().c_str());
00313   cur_simple_state_ = next_state;
00314 }
00315 
00316 template<class ActionSpec>
00317 void SimpleActionClient<ActionSpec>::sendGoal(const Goal & goal,
00318   SimpleDoneCallback done_cb,
00319   SimpleActiveCallback active_cb,
00320   SimpleFeedbackCallback feedback_cb)
00321 {
00322   // Reset the old GoalHandle, so that our callbacks won't get called anymore
00323   gh_.reset();
00324 
00325   // Store all the callbacks
00326   done_cb_ = done_cb;
00327   active_cb_ = active_cb;
00328   feedback_cb_ = feedback_cb;
00329 
00330   cur_simple_state_ = SimpleGoalState::PENDING;
00331 
00332   // Send the goal to the ActionServer
00333   gh_ = ac_->sendGoal(goal, boost::bind(&SimpleActionClientT::handleTransition, this, _1),
00334       boost::bind(&SimpleActionClientT::handleFeedback, this, _1, _2));
00335 }
00336 
00337 template<class ActionSpec>
00338 SimpleClientGoalState SimpleActionClient<ActionSpec>::getState() const
00339 {
00340   if (gh_.isExpired()) {
00341     return SimpleClientGoalState(SimpleClientGoalState::LOST);
00342   }
00343 
00344   CommState comm_state_ = gh_.getCommState();
00345 
00346   switch (comm_state_.state_) {
00347     case CommState::WAITING_FOR_GOAL_ACK:
00348     case CommState::PENDING:
00349     case CommState::RECALLING:
00350       return SimpleClientGoalState(SimpleClientGoalState::PENDING);
00351     case CommState::ACTIVE:
00352     case CommState::PREEMPTING:
00353       return SimpleClientGoalState(SimpleClientGoalState::ACTIVE);
00354     case CommState::DONE:
00355       {
00356         switch (gh_.getTerminalState().state_) {
00357           case TerminalState::RECALLED:
00358             return SimpleClientGoalState(SimpleClientGoalState::RECALLED,
00359                      gh_.getTerminalState().text_);
00360           case TerminalState::REJECTED:
00361             return SimpleClientGoalState(SimpleClientGoalState::REJECTED,
00362                      gh_.getTerminalState().text_);
00363           case TerminalState::PREEMPTED:
00364             return SimpleClientGoalState(SimpleClientGoalState::PREEMPTED,
00365                      gh_.getTerminalState().text_);
00366           case TerminalState::ABORTED:
00367             return SimpleClientGoalState(SimpleClientGoalState::ABORTED,
00368                      gh_.getTerminalState().text_);
00369           case TerminalState::SUCCEEDED:
00370             return SimpleClientGoalState(SimpleClientGoalState::SUCCEEDED,
00371                      gh_.getTerminalState().text_);
00372           case TerminalState::LOST:
00373             return SimpleClientGoalState(SimpleClientGoalState::LOST, gh_.getTerminalState().text_);
00374           default:
00375             ROS_ERROR_NAMED("actionlib",
00376               "Unknown terminal state [%u]. This is a bug in SimpleActionClient",
00377               gh_.getTerminalState().state_);
00378             return SimpleClientGoalState(SimpleClientGoalState::LOST, gh_.getTerminalState().text_);
00379         }
00380       }
00381     case CommState::WAITING_FOR_RESULT:
00382     case CommState::WAITING_FOR_CANCEL_ACK:
00383       {
00384         switch (cur_simple_state_.state_) {
00385           case SimpleGoalState::PENDING:
00386             return SimpleClientGoalState(SimpleClientGoalState::PENDING);
00387           case SimpleGoalState::ACTIVE:
00388             return SimpleClientGoalState(SimpleClientGoalState::ACTIVE);
00389           case SimpleGoalState::DONE:
00390             ROS_ERROR_NAMED("actionlib",
00391               "In WAITING_FOR_RESULT or WAITING_FOR_CANCEL_ACK, yet we are in SimpleGoalState DONE. This is a bug in SimpleActionClient");
00392             return SimpleClientGoalState(SimpleClientGoalState::LOST);
00393           default:
00394             ROS_ERROR_NAMED("actionlib",
00395               "Got a SimpleGoalState of [%u]. This is a bug in SimpleActionClient",
00396               cur_simple_state_.state_);
00397         }
00398       }
00399     default:
00400       break;
00401   }
00402   ROS_ERROR_NAMED("actionlib", "Error trying to interpret CommState - %u", comm_state_.state_);
00403   return SimpleClientGoalState(SimpleClientGoalState::LOST);
00404 }
00405 
00406 template<class ActionSpec>
00407 typename SimpleActionClient<ActionSpec>::ResultConstPtr SimpleActionClient<ActionSpec>::getResult()
00408 const
00409 {
00410   if (gh_.isExpired()) {
00411     ROS_ERROR_NAMED("actionlib",
00412       "Trying to getResult() when no goal is running. You are incorrectly using SimpleActionClient");
00413   }
00414 
00415   if (gh_.getResult()) {
00416     return gh_.getResult();
00417   }
00418 
00419   return ResultConstPtr(new Result);
00420 }
00421 
00422 
00423 template<class ActionSpec>
00424 void SimpleActionClient<ActionSpec>::cancelAllGoals()
00425 {
00426   ac_->cancelAllGoals();
00427 }
00428 
00429 template<class ActionSpec>
00430 void SimpleActionClient<ActionSpec>::cancelGoalsAtAndBeforeTime(const ros::Time & time)
00431 {
00432   ac_->cancelGoalsAtAndBeforeTime(time);
00433 }
00434 
00435 template<class ActionSpec>
00436 void SimpleActionClient<ActionSpec>::cancelGoal()
00437 {
00438   if (gh_.isExpired()) {
00439     ROS_ERROR_NAMED("actionlib",
00440       "Trying to cancelGoal() when no goal is running. You are incorrectly using SimpleActionClient");
00441   }
00442 
00443   gh_.cancel();
00444 }
00445 
00446 template<class ActionSpec>
00447 void SimpleActionClient<ActionSpec>::stopTrackingGoal()
00448 {
00449   if (gh_.isExpired()) {
00450     ROS_ERROR_NAMED("actionlib",
00451       "Trying to stopTrackingGoal() when no goal is running. You are incorrectly using SimpleActionClient");
00452   }
00453   gh_.reset();
00454 }
00455 
00456 template<class ActionSpec>
00457 void SimpleActionClient<ActionSpec>::handleFeedback(GoalHandleT gh,
00458   const FeedbackConstPtr & feedback)
00459 {
00460   if (gh_ != gh) {
00461     ROS_ERROR_NAMED("actionlib",
00462       "Got a callback on a goalHandle that we're not tracking.  \
00463                This is an internal SimpleActionClient/ActionClient bug.  \
00464                This could also be a GoalID collision");
00465   }
00466   if (feedback_cb_) {
00467     feedback_cb_(feedback);
00468   }
00469 }
00470 
00471 template<class ActionSpec>
00472 void SimpleActionClient<ActionSpec>::handleTransition(GoalHandleT gh)
00473 {
00474   CommState comm_state_ = gh.getCommState();
00475   switch (comm_state_.state_) {
00476     case CommState::WAITING_FOR_GOAL_ACK:
00477       ROS_ERROR_NAMED("actionlib",
00478         "BUG: Shouldn't ever get a transition callback for WAITING_FOR_GOAL_ACK");
00479       break;
00480     case CommState::PENDING:
00481       ROS_ERROR_COND(cur_simple_state_ != SimpleGoalState::PENDING,
00482         "BUG: Got a transition to CommState [%s] when our in SimpleGoalState [%s]",
00483         comm_state_.toString().c_str(), cur_simple_state_.toString().c_str());
00484       break;
00485     case CommState::ACTIVE:
00486       switch (cur_simple_state_.state_) {
00487         case SimpleGoalState::PENDING:
00488           setSimpleState(SimpleGoalState::ACTIVE);
00489           if (active_cb_) {
00490             active_cb_();
00491           }
00492           break;
00493         case SimpleGoalState::ACTIVE:
00494           break;
00495         case SimpleGoalState::DONE:
00496           ROS_ERROR_NAMED("actionlib",
00497             "BUG: Got a transition to CommState [%s] when in SimpleGoalState [%s]",
00498             comm_state_.toString().c_str(), cur_simple_state_.toString().c_str());
00499           break;
00500         default:
00501           ROS_FATAL("Unknown SimpleGoalState %u", cur_simple_state_.state_);
00502           break;
00503       }
00504       break;
00505     case CommState::WAITING_FOR_RESULT:
00506       break;
00507     case CommState::WAITING_FOR_CANCEL_ACK:
00508       break;
00509     case CommState::RECALLING:
00510       ROS_ERROR_COND(cur_simple_state_ != SimpleGoalState::PENDING,
00511         "BUG: Got a transition to CommState [%s] when our in SimpleGoalState [%s]",
00512         comm_state_.toString().c_str(), cur_simple_state_.toString().c_str());
00513       break;
00514     case CommState::PREEMPTING:
00515       switch (cur_simple_state_.state_) {
00516         case SimpleGoalState::PENDING:
00517           setSimpleState(SimpleGoalState::ACTIVE);
00518           if (active_cb_) {
00519             active_cb_();
00520           }
00521           break;
00522         case SimpleGoalState::ACTIVE:
00523           break;
00524         case SimpleGoalState::DONE:
00525           ROS_ERROR_NAMED("actionlib",
00526             "BUG: Got a transition to CommState [%s] when in SimpleGoalState [%s]",
00527             comm_state_.toString().c_str(), cur_simple_state_.toString().c_str());
00528           break;
00529         default:
00530           ROS_FATAL("Unknown SimpleGoalState %u", cur_simple_state_.state_);
00531           break;
00532       }
00533       break;
00534     case CommState::DONE:
00535       switch (cur_simple_state_.state_) {
00536         case SimpleGoalState::PENDING:
00537         case SimpleGoalState::ACTIVE:
00538           {
00539             boost::mutex::scoped_lock lock(done_mutex_);
00540             setSimpleState(SimpleGoalState::DONE);
00541           }
00542 
00543           if (done_cb_) {
00544             done_cb_(getState(), gh.getResult());
00545           }
00546 
00547           done_condition_.notify_all();
00548           break;
00549         case SimpleGoalState::DONE:
00550           ROS_ERROR_NAMED("actionlib", "BUG: Got a second transition to DONE");
00551           break;
00552         default:
00553           ROS_FATAL("Unknown SimpleGoalState %u", cur_simple_state_.state_);
00554           break;
00555       }
00556       break;
00557     default:
00558       ROS_ERROR_NAMED("actionlib", "Unknown CommState received [%u]", comm_state_.state_);
00559       break;
00560   }
00561 }
00562 
00563 template<class ActionSpec>
00564 bool SimpleActionClient<ActionSpec>::waitForResult(const ros::Duration & timeout)
00565 {
00566   if (gh_.isExpired()) {
00567     ROS_ERROR_NAMED("actionlib",
00568       "Trying to waitForGoalToFinish() when no goal is running. You are incorrectly using SimpleActionClient");
00569     return false;
00570   }
00571 
00572   if (timeout < ros::Duration(0, 0)) {
00573     ROS_WARN_NAMED("actionlib", "Timeouts can't be negative. Timeout is [%.2fs]", timeout.toSec());
00574   }
00575 
00576   ros::Time timeout_time = ros::Time::now() + timeout;
00577 
00578   boost::mutex::scoped_lock lock(done_mutex_);
00579 
00580   // Hardcode how often we check for node.ok()
00581   ros::Duration loop_period = ros::Duration().fromSec(.1);
00582 
00583   while (nh_.ok()) {
00584     // Determine how long we should wait
00585     ros::Duration time_left = timeout_time - ros::Time::now();
00586 
00587     // Check if we're past the timeout time
00588     if (timeout > ros::Duration(0, 0) && time_left <= ros::Duration(0, 0) ) {
00589       break;
00590     }
00591 
00592     if (cur_simple_state_ == SimpleGoalState::DONE) {
00593       break;
00594     }
00595 
00596 
00597     // Truncate the time left
00598     if (time_left > loop_period || timeout == ros::Duration()) {
00599       time_left = loop_period;
00600     }
00601 
00602     done_condition_.timed_wait(lock,
00603       boost::posix_time::milliseconds(static_cast<int64_t>(time_left.toSec() * 1000.0f)));
00604   }
00605 
00606   return cur_simple_state_ == SimpleGoalState::DONE;
00607 }
00608 
00609 template<class ActionSpec>
00610 SimpleClientGoalState SimpleActionClient<ActionSpec>::sendGoalAndWait(const Goal & goal,
00611   const ros::Duration & execute_timeout,
00612   const ros::Duration & preempt_timeout)
00613 {
00614   sendGoal(goal);
00615 
00616   // See if the goal finishes in time
00617   if (waitForResult(execute_timeout)) {
00618     ROS_DEBUG_NAMED("actionlib", "Goal finished within specified execute_timeout [%.2f]",
00619       execute_timeout.toSec());
00620     return getState();
00621   }
00622 
00623   ROS_DEBUG_NAMED("actionlib", "Goal didn't finish within specified execute_timeout [%.2f]",
00624     execute_timeout.toSec());
00625 
00626   // It didn't finish in time, so we need to preempt it
00627   cancelGoal();
00628 
00629   // Now wait again and see if it finishes
00630   if (waitForResult(preempt_timeout)) {
00631     ROS_DEBUG_NAMED("actionlib", "Preempt finished within specified preempt_timeout [%.2f]",
00632       preempt_timeout.toSec());
00633   } else {
00634     ROS_DEBUG_NAMED("actionlib", "Preempt didn't finish specified preempt_timeout [%.2f]",
00635       preempt_timeout.toSec());
00636   }
00637   return getState();
00638 }
00639 
00640 }  // namespace actionlib
00641 
00642 #undef DEPRECATED
00643 
00644 #endif  // ACTIONLIB__CLIENT__SIMPLE_ACTION_CLIENT_H_


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Sat Feb 16 2019 03:21:28