#include <queued_action_server.h>
Public Types | |
| typedef boost::function< void(const GoalConstPtr &)> | ExecuteCallback |
| typedef ActionServer< ActionSpec >::GoalHandle | GoalHandle |
Public Member Functions | |
| boost::shared_ptr< const Goal > | acceptNewGoal () |
| ACTION_DEFINITION (ActionSpec) | |
| bool | isActive () |
| bool | isNewGoalAvailable () |
| bool | isPreemptRequested () |
| QueuedActionServer (std::string name, ExecuteCallback execute_callback) | |
| QueuedActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_callback) | |
| void | setAborted (const Result &result=Result(), const std::string &text=std::string("")) |
| void | setPreempted (const Result &result=Result(), const std::string &text=std::string("")) |
| void | setSucceeded (const Result &result=Result(), const std::string &text=std::string("")) |
| void | shutdown () |
| void | start () |
| ~QueuedActionServer () | |
Private Member Functions | |
| void | executeLoop () |
| void | goalCallback (GoalHandle preempt) |
| void | preemptCallback (GoalHandle preempt) |
Private Attributes | |
| std::shared_ptr< ActionServer< ActionSpec > > | as |
| GoalHandle | current_goal |
| ExecuteCallback | execute_callback |
| std::condition_variable_any | execute_condition |
| std::thread * | execute_thread |
| std::recursive_mutex | lock |
| ros::NodeHandle | n_ |
| std::atomic< bool > | need_to_terminate |
| bool | new_goal_ |
| bool | new_goal_preempt_request_ |
| GoalHandle | next_goal |
| bool | preempt_request_ |
Definition at line 51 of file queued_action_server.h.
| typedef boost::function<void(const GoalConstPtr &)> actionlib::QueuedActionServer< ActionSpec >::ExecuteCallback |
Definition at line 58 of file queued_action_server.h.
| typedef ActionServer<ActionSpec>::GoalHandle actionlib::QueuedActionServer< ActionSpec >::GoalHandle |
Definition at line 57 of file queued_action_server.h.
| actionlib::QueuedActionServer< ActionSpec >::QueuedActionServer | ( | std::string | name, |
| ExecuteCallback | execute_callback | ||
| ) |
Definition at line 47 of file queued_action_server_imp.h.
| actionlib::QueuedActionServer< ActionSpec >::QueuedActionServer | ( | ros::NodeHandle | n, |
| std::string | name, | ||
| ExecuteCallback | execute_callback | ||
| ) |
Definition at line 66 of file queued_action_server_imp.h.
| actionlib::QueuedActionServer< ActionSpec >::~QueuedActionServer | ( | ) |
Definition at line 86 of file queued_action_server_imp.h.
| boost::shared_ptr< const typename QueuedActionServer< ActionSpec >::Goal > actionlib::QueuedActionServer< ActionSpec >::acceptNewGoal | ( | ) |
Definition at line 108 of file queued_action_server_imp.h.
| actionlib::QueuedActionServer< ActionSpec >::ACTION_DEFINITION | ( | ActionSpec | ) |
|
private |
Definition at line 226 of file queued_action_server_imp.h.
|
private |
Definition at line 175 of file queued_action_server_imp.h.
| bool actionlib::QueuedActionServer< ActionSpec >::isActive | ( | ) |
Definition at line 144 of file queued_action_server_imp.h.
| bool actionlib::QueuedActionServer< ActionSpec >::isNewGoalAvailable | ( | ) |
Definition at line 134 of file queued_action_server_imp.h.
| bool actionlib::QueuedActionServer< ActionSpec >::isPreemptRequested | ( | ) |
Definition at line 139 of file queued_action_server_imp.h.
|
private |
Definition at line 206 of file queued_action_server_imp.h.
| void actionlib::QueuedActionServer< ActionSpec >::setAborted | ( | const Result & | result = Result(), |
| const std::string & | text = std::string("") |
||
| ) |
Definition at line 161 of file queued_action_server_imp.h.
| void actionlib::QueuedActionServer< ActionSpec >::setPreempted | ( | const Result & | result = Result(), |
| const std::string & | text = std::string("") |
||
| ) |
Definition at line 168 of file queued_action_server_imp.h.
| void actionlib::QueuedActionServer< ActionSpec >::setSucceeded | ( | const Result & | result = Result(), |
| const std::string & | text = std::string("") |
||
| ) |
Definition at line 154 of file queued_action_server_imp.h.
| void actionlib::QueuedActionServer< ActionSpec >::shutdown | ( | ) |
Definition at line 93 of file queued_action_server_imp.h.
| void actionlib::QueuedActionServer< ActionSpec >::start | ( | ) |
Definition at line 272 of file queued_action_server_imp.h.
|
private |
Definition at line 82 of file queued_action_server.h.
|
private |
Definition at line 84 of file queued_action_server.h.
|
private |
Definition at line 90 of file queued_action_server.h.
|
private |
Definition at line 91 of file queued_action_server.h.
|
private |
Definition at line 92 of file queued_action_server.h.
|
private |
Definition at line 88 of file queued_action_server.h.
|
private |
Definition at line 80 of file queued_action_server.h.
|
private |
Definition at line 94 of file queued_action_server.h.
|
private |
Definition at line 86 of file queued_action_server.h.
|
private |
Definition at line 86 of file queued_action_server.h.
|
private |
Definition at line 84 of file queued_action_server.h.
|
private |
Definition at line 86 of file queued_action_server.h.