12 #include <condition_variable>
25 template <
class ActionSpec>
36 bool autoStart = false)
39 actionServer = ensenso::std::make_unique<actionlib::ActionServer<ActionSpec>>(
nh,
name,
false);
67 std::lock_guard<std::mutex> lock(
mutex);
75 std::lock_guard<std::mutex> lock(
mutex);
83 std::lock_guard<std::mutex> lock(
mutex);
117 std::lock_guard<std::mutex> lock(
mutex);
126 std::lock_guard<std::mutex> lock(
mutex);
137 goal.setCanceled(Result(),
"Goal was canceled by the user.");
143 std::unique_lock<std::mutex> lock(
mutex);
156 else if (
currentGoal.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING)
158 currentGoal.setCanceled(Result(),
"Goal was canceled by the user.");
160 else if (
currentGoal.getGoalStatus().status != actionlib_msgs::GoalStatus::PENDING)
176 if (
currentGoal.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE ||
177 currentGoal.getGoalStatus().status == actionlib_msgs::GoalStatus::PREEMPTING)
180 "Your action handler did not set the goal to a terminal state. Aborting it for now.");
186 loopCondition.wait_for(lock, std::chrono::milliseconds(100));