4 #include <condition_variable> 23 template <
class ActionSpec>
34 bool autoStart = false)
35 : nodeHandle(nodeHandle), callback(callback)
72 void setSucceeded(Result
const& result = Result(), std::string
const& text =
"")
74 std::lock_guard<std::mutex> lock(
mutex);
80 void setAborted(Result
const& result = Result(), std::string
const& text =
"")
82 std::lock_guard<std::mutex> lock(
mutex);
88 void setPreempted(Result
const& result = Result(), std::string
const& text =
"")
90 std::lock_guard<std::mutex> lock(
mutex);
110 std::lock_guard<std::mutex> lock(
mutex);
119 std::lock_guard<std::mutex> lock(
mutex);
132 goal.setCanceled(Result(),
"Goal was canceled by the user.");
138 std::unique_lock<std::mutex> lock(
mutex);
150 else if (
currentGoal.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
152 currentGoal.setCanceled(Result(),
"Goal was canceled by the user.");
154 else if (
currentGoal.getGoalStatus().status != actionlib_msgs::GoalStatus::PENDING)
171 if (
currentGoal.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE ||
172 currentGoal.getGoalStatus().status == actionlib_msgs::GoalStatus::PREEMPTING)
174 ROS_WARN_NAMED(
"actionlib",
"Your action handler did not set the " 175 "goal to a terminal state. Aborting it " 177 setAborted(Result(),
"Aborted, because the user did not set the " 178 "goal to a terminal state.");
183 loopCondition.wait_for(lock, std::chrono::milliseconds(100));
void setPreempted(Result const &result=Result(), std::string const &text="")
typename actionlib::ActionServer< ActionSpec >::GoalHandle GoalHandle
bool isPreemptRequested()
volatile bool shutdownRequested
#define ROS_WARN_NAMED(name,...)
void onCancelReceived(GoalHandle goal)
void setAborted(Result const &result=Result(), std::string const &text="")
void publishFeedback(Feedback const &feedback)
boost::function< void(GoalConstPtr const &)> ExecuteCallback
#define ROS_DEBUG_NAMED(name,...)
std::queue< GoalHandle > goalQueue
std::unique_ptr< actionlib::ActionServer< ActionSpec > > actionServer
std::condition_variable loopCondition
#define ACTION_DEFINITION(ActionSpec)
ros::NodeHandle nodeHandle
void onGoalReceived(GoalHandle goal)
void setSucceeded(Result const &result=Result(), std::string const &text="")
void publishFeedback(FeedbackConstPtr const &feedback)