36 #ifndef QUEUED_ACTION_SERVER_H_ 37 #define QUEUED_ACTION_SERVER_H_ 43 #include <condition_variable> 50 template <
class ActionSpec>
68 void setSucceeded(
const Result &result = Result(),
const std::string &text = std::string(
""));
69 void setAborted(
const Result &result = Result(),
const std::string &text = std::string(
""));
70 void setPreempted(
const Result &result = Result(),
const std::string &text = std::string(
""));
82 std::shared_ptr<ActionServer<ActionSpec>>
as;
bool isPreemptRequested()
ExecuteCallback execute_callback
std::thread * execute_thread
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
std::condition_variable_any execute_condition
std::atomic< bool > need_to_terminate
void goalCallback(GoalHandle preempt)
std::shared_ptr< ActionServer< ActionSpec > > as
QueuedActionServer(std::string name, ExecuteCallback execute_callback)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
bool isNewGoalAvailable()
bool new_goal_preempt_request_
boost::shared_ptr< const Goal > acceptNewGoal()
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
void preemptCallback(GoalHandle preempt)
std::recursive_mutex lock
boost::function< void(const GoalConstPtr &)> ExecuteCallback
ACTION_DEFINITION(ActionSpec)
ActionServer< ActionSpec >::GoalHandle GoalHandle