Codebase list ros-actionlib / 655a845
New upstream version 1.11.11 Jochen Sprickerhof 6 years ago
8 changed file(s) with 21 addition(s) and 18 deletion(s). Raw diff Collapse all Expand all
00 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
11 Changelog for package actionlib
22 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
3
4 1.11.11 (2017-10-27)
5 --------------------
6 * fix typo in server_goal_handle_imp.h (`#89 <https://github.com/ros/actionlib/issues/89>`_)
7 * Use RAII to handle mutexes (`#87 <https://github.com/ros/actionlib/issues/87>`_)
8 * Contributors: Cong Liu, Esteve Fernandez, Mikael Arguedas
39
410 1.11.10 (2017-07-27)
511 --------------------
536536 switch (cur_simple_state_.state_) {
537537 case SimpleGoalState::PENDING:
538538 case SimpleGoalState::ACTIVE:
539 done_mutex_.lock();
540 setSimpleState(SimpleGoalState::DONE);
541 done_mutex_.unlock();
539 {
540 boost::mutex::scoped_lock lock(done_mutex_);
541 setSimpleState(SimpleGoalState::DONE);
542 }
542543
543544 if (done_cb_) {
544545 done_cb_(getState(), gh.getResult());
3838
3939 #include <ros/ros.h>
4040 #include <boost/thread.hpp>
41 #include <boost/thread/reverse_lock.hpp>
4142 #include <boost/shared_ptr.hpp>
4243 #include <actionlib_msgs/GoalID.h>
4344 #include <actionlib_msgs/GoalStatusArray.h>
252252 GoalHandle gh = GoalHandle(it, this, handle_tracker, guard_);
253253
254254 // make sure that we unlock before calling the users callback
255 lock_.unlock();
255 boost::reverse_lock<boost::recursive_mutex::scoped_lock> unlocker(lock);
256256
257257 // now, we need to create a goal handle and call the user's callback
258258 goal_callback_(gh);
259
260 lock_.lock();
261259 }
262260 }
263261
309307 GoalHandle gh(it, this, handle_tracker, guard_);
310308 if (gh.setCancelRequested()) {
311309 // make sure that we're unlocked before we call the users callback
312 lock_.unlock();
310 boost::reverse_lock<boost::recursive_mutex::scoped_lock> unlocker(lock);
313311
314312 // call the user's cancel callback on the relevant goal
315313 cancel_callback_(gh);
316
317 // lock for further modification of the status list
318 lock_.lock();
319314 }
320315 }
321316 }
5454 DestructionGuard::ScopedProtector protector(*guard_);
5555 if (protector.isProtected()) {
5656 // make sure to lock while we erase status for this goal from the list
57 as_->lock_.lock();
57 boost::recursive_mutex::scoped_lock lock(as_->lock_);
5858 (*status_it_).handle_destruction_time_ = ros::Time::now();
5959 // as_->status_list_.erase(status_it_);
60 as_->lock_.unlock();
6160 }
6261 }
6362 }
392392 }
393393
394394 ROS_DEBUG_NAMED("actionlib",
395 "Transisitoning to a cancel requested state on goal id: %s, stamp: %.2f",
395 "Transitioning to a cancel requested state on goal id: %s, stamp: %.2f",
396396 getGoalID().id.c_str(), getGoalID().stamp.toSec());
397397 if (goal_) {
398398 boost::recursive_mutex::scoped_lock lock(as_->lock_);
384384 ROS_FATAL_COND(!execute_callback_,
385385 "execute_callback_ must exist. This is a bug in SimpleActionServer");
386386
387 // Make sure we're not locked when we call execute
388 lock.unlock();
389 execute_callback_(goal);
390 lock.lock();
387 {
388 // Make sure we're not locked when we call execute
389 boost::reverse_lock<boost::recursive_mutex::scoped_lock> unlocker(lock);
390 execute_callback_(goal);
391 }
391392
392393 if (isActive()) {
393394 ROS_WARN_NAMED("actionlib", "Your executeCallback did not set the goal to a terminal status.\n"
11 <?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
22 <package format="2">
33 <name>actionlib</name>
4 <version>1.11.10</version>
4 <version>1.11.11</version>
55 <description>
66 The actionlib stack provides a standardized interface for
77 interfacing with preemptable tasks. Examples of this include moving