while (n_.ok()) { { boost::mutex::scoped_lock terminate_lock(terminate_mutex_); if (need_to_terminate_) // 只在 shutdown() 函数中为 true break; } boost::recursive_mutex::scoped_lock lock(lock_); if (isActive()) ROS_ERROR_NAMED("actionlib", "Should never reach this code with an active goal");
ROS_FATAL_COND(!execute_callback_, "execute_callback_ must exist. This is a bug in SimpleActionServer");
// Make sure we're not locked when we call execute // 重新以新的goal执行executecallback函数 lock.unlock(); execute_callback_(goal); lock.lock();
if (isActive()) { ROS_WARN_NAMED("actionlib", "Your executeCallback did not set the goal to a terminal status.\n" "This is a bug in your ActionServer implementation. Fix your code!\n" "For now, the ActionServer will set this goal to aborted"); setAborted(Result(), "This goal was aborted by the simple action server. The user should have set a terminal status on this goal and did not"); } } // 如果没有新目标,通过条件变量将线程阻塞 else execute_condition_.timed_wait(lock, boost::posix_time::milliseconds(loop_duration.toSec() * 1000.0f)); } }