00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef ACTIONLIB_ACTION_SERVER_IMP_H_
00038 #define ACTIONLIB_ACTION_SERVER_IMP_H_
00039 namespace actionlib {
00040 template <class ActionSpec>
00041 ActionServer<ActionSpec>::ActionServer(ros::NodeHandle n, std::string name,
00042 bool auto_start)
00043 : node_(n, name), goal_callback_(boost::function<void (GoalHandle)>()),
00044 cancel_callback_(boost::function<void (GoalHandle)>()), started_(auto_start), guard_(new DestructionGuard){
00045
00046 if(started_){
00047 ROS_WARN("You've passed in true for auto_start for the C++ action server you should always pass in false to avoid race conditions.");
00048 initialize();
00049 publishStatus();
00050 }
00051 }
00052
00053 template <class ActionSpec>
00054 ActionServer<ActionSpec>::ActionServer(ros::NodeHandle n, std::string name)
00055 : node_(n, name), goal_callback_(boost::function<void (GoalHandle)>()),
00056 cancel_callback_(boost::function<void (GoalHandle)>()), started_(true), guard_(new DestructionGuard){
00057
00058 if(started_){
00059 ROS_WARN("You've passed in true for auto_start for the C++ action server you should always pass in false to avoid race conditions.");
00060 initialize();
00061 publishStatus();
00062 }
00063 }
00064
00065 template <class ActionSpec>
00066 ActionServer<ActionSpec>::ActionServer(ros::NodeHandle n, std::string name,
00067 boost::function<void (GoalHandle)> goal_cb,
00068 boost::function<void (GoalHandle)> cancel_cb,
00069 bool auto_start)
00070 : node_(n, name), goal_callback_(goal_cb), cancel_callback_(cancel_cb), started_(auto_start), guard_(new DestructionGuard) {
00071
00072 if(started_){
00073 ROS_WARN("You've passed in true for auto_start for the C++ action server you should always pass in false to avoid race conditions.");
00074 initialize();
00075 publishStatus();
00076 }
00077 }
00078
00079 template <class ActionSpec>
00080 ActionServer<ActionSpec>::ActionServer(ros::NodeHandle n, std::string name,
00081 boost::function<void (GoalHandle)> goal_cb,
00082 boost::function<void (GoalHandle)> cancel_cb)
00083 : node_(n, name), goal_callback_(goal_cb), cancel_callback_(cancel_cb), started_(true), guard_(new DestructionGuard) {
00084
00085 if(started_){
00086 ROS_WARN("You've passed in true for auto_start for the C++ action server you should always pass in false to avoid race conditions.");
00087 initialize();
00088 publishStatus();
00089 }
00090 }
00091
00092 template <class ActionSpec>
00093 ActionServer<ActionSpec>::ActionServer(ros::NodeHandle n, std::string name,
00094 boost::function<void (GoalHandle)> goal_cb,
00095 bool auto_start)
00096 : node_(n, name), goal_callback_(goal_cb), cancel_callback_(boost::function<void (GoalHandle)>()), started_(auto_start), guard_(new DestructionGuard) {
00097
00098 if(started_){
00099 ROS_WARN("You've passed in true for auto_start for the C++ action server you should always pass in false to avoid race conditions.");
00100 initialize();
00101 publishStatus();
00102 }
00103 }
00104
00105 template <class ActionSpec>
00106 ActionServer<ActionSpec>::~ActionServer(){
00107
00108 guard_->destruct();
00109 }
00110
00111 template <class ActionSpec>
00112 void ActionServer<ActionSpec>::initialize(){
00113 result_pub_ = node_.advertise<ActionResult>("result", 50);
00114 feedback_pub_ = node_.advertise<ActionFeedback>("feedback", 50);
00115 status_pub_ = node_.advertise<actionlib_msgs::GoalStatusArray>("status", 50);
00116
00117
00118 double status_frequency, status_list_timeout;
00119 node_.param("status_frequency", status_frequency, 5.0);
00120 node_.param("status_list_timeout", status_list_timeout, 5.0);
00121
00122 status_list_timeout_ = ros::Duration(status_list_timeout);
00123
00124 if(status_frequency > 0){
00125 status_timer_ = node_.createTimer(ros::Duration(1.0 / status_frequency),
00126 boost::bind(&ActionServer::publishStatus, this, _1));
00127 }
00128
00129 goal_sub_ = node_.subscribe<ActionGoal>("goal", 50,
00130 boost::bind(&ActionServer::goalCallback, this, _1));
00131
00132 cancel_sub_ = node_.subscribe<actionlib_msgs::GoalID>("cancel", 50,
00133 boost::bind(&ActionServer::cancelCallback, this, _1));
00134
00135 }
00136
00137 template <class ActionSpec>
00138 void ActionServer<ActionSpec>::registerGoalCallback(boost::function<void (GoalHandle)> cb){
00139 goal_callback_ = cb;
00140 }
00141
00142 template <class ActionSpec>
00143 void ActionServer<ActionSpec>::registerCancelCallback(boost::function<void (GoalHandle)> cb){
00144 cancel_callback_ = cb;
00145 }
00146
00147 template <class ActionSpec>
00148 void ActionServer<ActionSpec>::publishResult(const actionlib_msgs::GoalStatus& status, const Result& result){
00149 boost::recursive_mutex::scoped_lock lock(lock_);
00150
00151 boost::shared_ptr<ActionResult> ar(new ActionResult);
00152 ar->header.stamp = ros::Time::now();
00153 ar->status = status;
00154 ar->result = result;
00155 ROS_DEBUG("Publishing result for goal with id: %s and stamp: %.2f", status.goal_id.id.c_str(), status.goal_id.stamp.toSec());
00156 result_pub_.publish(ar);
00157 }
00158
00159 template <class ActionSpec>
00160 void ActionServer<ActionSpec>::publishFeedback(const actionlib_msgs::GoalStatus& status, const Feedback& feedback){
00161 boost::recursive_mutex::scoped_lock lock(lock_);
00162
00163 boost::shared_ptr<ActionFeedback> af(new ActionFeedback);
00164 af->header.stamp = ros::Time::now();
00165 af->status = status;
00166 af->feedback = feedback;
00167 ROS_DEBUG("Publishing feedback for goal with id: %s and stamp: %.2f", status.goal_id.id.c_str(), status.goal_id.stamp.toSec());
00168 feedback_pub_.publish(af);
00169 }
00170
00171 template <class ActionSpec>
00172 void ActionServer<ActionSpec>::cancelCallback(const boost::shared_ptr<const actionlib_msgs::GoalID>& goal_id){
00173 boost::recursive_mutex::scoped_lock lock(lock_);
00174
00175
00176 if(!started_)
00177 return;
00178
00179
00180 ROS_DEBUG("The action server has received a new cancel request");
00181 bool goal_id_found = false;
00182 for(typename std::list<StatusTracker<ActionSpec> >::iterator it = status_list_.begin(); it != status_list_.end(); ++it){
00183
00184
00185 if(
00186 (goal_id->id == "" && goal_id->stamp == ros::Time())
00187 || goal_id->id == (*it).status_.goal_id.id
00188 || (goal_id->stamp != ros::Time() && (*it).status_.goal_id.stamp <= goal_id->stamp)
00189 ){
00190
00191 if(goal_id->id == (*it).status_.goal_id.id)
00192 goal_id_found = true;
00193
00194
00195 boost::shared_ptr<void> handle_tracker = (*it).handle_tracker_.lock();
00196
00197 if((*it).handle_tracker_.expired()){
00198
00199 HandleTrackerDeleter<ActionSpec> d(this, it, guard_);
00200 handle_tracker = boost::shared_ptr<void>((void *)NULL, d);
00201 (*it).handle_tracker_ = handle_tracker;
00202
00203
00204 (*it).handle_destruction_time_ = ros::Time();
00205 }
00206
00207
00208
00209 GoalHandle gh(it, this, handle_tracker, guard_);
00210 if(gh.setCancelRequested()){
00211
00212 lock_.unlock();
00213
00214
00215 cancel_callback_(gh);
00216
00217
00218 lock_.lock();
00219 }
00220 }
00221 }
00222
00223
00224 if(goal_id->id != "" && !goal_id_found){
00225 typename std::list<StatusTracker<ActionSpec> >::iterator it = status_list_.insert(status_list_.end(),
00226 StatusTracker<ActionSpec> (*goal_id, actionlib_msgs::GoalStatus::RECALLING));
00227
00228 (*it).handle_destruction_time_ = ros::Time::now();
00229 }
00230
00231
00232 if(goal_id->stamp > last_cancel_)
00233 last_cancel_ = goal_id->stamp;
00234 }
00235
00236 template <class ActionSpec>
00237 void ActionServer<ActionSpec>::goalCallback(const boost::shared_ptr<const ActionGoal>& goal){
00238 boost::recursive_mutex::scoped_lock lock(lock_);
00239
00240
00241 if(!started_)
00242 return;
00243
00244 ROS_DEBUG("The action server has received a new goal request");
00245
00246
00247 for(typename std::list<StatusTracker<ActionSpec> >::iterator it = status_list_.begin(); it != status_list_.end(); ++it){
00248 if(goal->goal_id.id == (*it).status_.goal_id.id){
00249
00250
00251 if ( (*it).status_.status == actionlib_msgs::GoalStatus::RECALLING ) {
00252 (*it).status_.status = actionlib_msgs::GoalStatus::RECALLED;
00253 publishResult((*it).status_, Result());
00254 }
00255
00256
00257
00258 if((*it).handle_tracker_.expired()){
00259 (*it).handle_destruction_time_ = ros::Time::now();
00260 }
00261
00262
00263 return;
00264 }
00265 }
00266
00267
00268 typename std::list<StatusTracker<ActionSpec> >::iterator it = status_list_.insert(status_list_.end(), StatusTracker<ActionSpec> (goal));
00269
00270
00271 HandleTrackerDeleter<ActionSpec> d(this, it, guard_);
00272 boost::shared_ptr<void> handle_tracker((void *)NULL, d);
00273 (*it).handle_tracker_ = handle_tracker;
00274
00275
00276 if(goal->goal_id.stamp != ros::Time() && goal->goal_id.stamp <= last_cancel_){
00277
00278 GoalHandle gh(it, this, handle_tracker, guard_);
00279 gh.setCanceled(Result(), "This goal handle was canceled by the action server because its timestamp is before the timestamp of the last cancel request");
00280 }
00281 else{
00282 GoalHandle gh = GoalHandle(it, this, handle_tracker, guard_);
00283
00284
00285 lock_.unlock();
00286
00287
00288 goal_callback_(gh);
00289
00290 lock_.lock();
00291 }
00292 }
00293
00294 template <class ActionSpec>
00295 void ActionServer<ActionSpec>::start(){
00296 initialize();
00297 started_ = true;
00298 publishStatus();
00299 }
00300
00301 template <class ActionSpec>
00302 void ActionServer<ActionSpec>::publishStatus(const ros::TimerEvent& e){
00303 boost::recursive_mutex::scoped_lock lock(lock_);
00304
00305 if(!started_)
00306 return;
00307
00308 publishStatus();
00309 }
00310
00311 template <class ActionSpec>
00312 void ActionServer<ActionSpec>::publishStatus(){
00313 boost::recursive_mutex::scoped_lock lock(lock_);
00314
00315 actionlib_msgs::GoalStatusArray status_array;
00316
00317 status_array.header.stamp = ros::Time::now();
00318
00319 status_array.status_list.resize(status_list_.size());
00320
00321 unsigned int i = 0;
00322 for(typename std::list<StatusTracker<ActionSpec> >::iterator it = status_list_.begin(); it != status_list_.end();){
00323 status_array.status_list[i] = (*it).status_;
00324
00325
00326 if((*it).handle_destruction_time_ != ros::Time()
00327 && (*it).handle_destruction_time_ + status_list_timeout_ < ros::Time::now()){
00328 it = status_list_.erase(it);
00329 }
00330 else
00331 ++it;
00332
00333 ++i;
00334 }
00335
00336 status_pub_.publish(status_array);
00337 }
00338 };
00339 #endif