The ActionServerBase implements the logic for an ActionServer.
More...
#include <action_server_base.h>
|
virtual void | initialize ()=0 |
| Initialize all ROS connections and setup timers. More...
|
|
virtual void | publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback)=0 |
| Publishes feedback for a given goal. More...
|
|
virtual void | publishResult (const actionlib_msgs::GoalStatus &status, const Result &result)=0 |
| Publishes a result for a given goal. More...
|
|
virtual void | publishStatus ()=0 |
| Explicitly publish status. More...
|
|
template<class ActionSpec>
class actionlib::ActionServerBase< ActionSpec >
The ActionServerBase implements the logic for an ActionServer.
Definition at line 99 of file action_server_base.h.
◆ GoalHandle
template<class ActionSpec >
◆ ActionServerBase()
template<class ActionSpec >
Constructor for an ActionServer.
- Parameters
-
goal_cb | A goal callback to be called when the ActionServer receives a new goal over the wire |
cancel_cb | A cancel callback to be called when the ActionServer receives a new cancel request over the wire |
auto_start | A boolean value that tells the ActionServer whether or not to start publishing as soon as it comes up. THIS SHOULD ALWAYS BE SET TO FALSE TO AVOID RACE CONDITIONS and start() should be called after construction of the server. |
Definition at line 199 of file action_server_base.h.
◆ ~ActionServerBase()
template<class ActionSpec >
◆ cancelCallback()
template<class ActionSpec >
◆ goalCallback()
template<class ActionSpec >
◆ initialize()
template<class ActionSpec >
◆ publishFeedback()
template<class ActionSpec >
virtual void actionlib::ActionServerBase< ActionSpec >::publishFeedback |
( |
const actionlib_msgs::GoalStatus & |
status, |
|
|
const Feedback & |
feedback |
|
) |
| |
|
protectedpure virtual |
◆ publishResult()
template<class ActionSpec >
virtual void actionlib::ActionServerBase< ActionSpec >::publishResult |
( |
const actionlib_msgs::GoalStatus & |
status, |
|
|
const Result & |
result |
|
) |
| |
|
protectedpure virtual |
◆ publishStatus()
template<class ActionSpec >
◆ registerCancelCallback()
template<class ActionSpec >
Register a callback to be invoked when a new cancel is received, this will replace any previously registered callback.
- Parameters
-
Definition at line 224 of file action_server_base.h.
◆ registerGoalCallback()
template<class ActionSpec >
Register a callback to be invoked when a new goal is received, this will replace any previously registered callback.
- Parameters
-
Definition at line 218 of file action_server_base.h.
◆ start()
template<class ActionSpec >
Explicitly start the action server, used it auto_start is set to false.
Definition at line 230 of file action_server_base.h.
◆ HandleTrackerDeleter< ActionSpec >
template<class ActionSpec >
◆ ServerGoalHandle< ActionSpec >
template<class ActionSpec >
◆ cancel_callback_
template<class ActionSpec >
◆ goal_callback_
template<class ActionSpec >
◆ guard_
template<class ActionSpec >
◆ id_generator_
template<class ActionSpec >
◆ last_cancel_
template<class ActionSpec >
◆ lock_
template<class ActionSpec >
◆ started_
template<class ActionSpec >
◆ status_list_
template<class ActionSpec >
◆ status_list_timeout_
template<class ActionSpec >
The documentation for this class was generated from the following file: