Full interface to an ActionServer. More...
#include <action_client.h>
Public Types | |
typedef ClientGoalHandle< ActionSpec > | GoalHandle |
Public Member Functions | |
ActionClient (const std::string &name, ros::CallbackQueueInterface *queue=NULL) | |
Simple constructor. More... | |
ActionClient (const ros::NodeHandle &n, const std::string &name, ros::CallbackQueueInterface *queue=NULL) | |
Constructor with namespacing options. More... | |
void | cancelAllGoals () |
Cancel all goals currently running on the action server. More... | |
void | cancelGoalsAtAndBeforeTime (const ros::Time &time) |
Cancel all goals that were stamped at and before the specified time. More... | |
bool | isServerConnected () |
Checks if the action client is successfully connected to the action server. More... | |
GoalHandle | sendGoal (const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback()) |
Sends a goal to the ActionServer, and also registers callbacks. More... | |
bool | waitForActionServerToStart (const ros::Duration &timeout=ros::Duration(0, 0)) |
Waits for the ActionServer to connect to this client Often, it can take a second for the action server & client to negotiate a connection, thus, risking the first few goals to be dropped. This call lets the user wait until the network connection to the server is negotiated NOTE: Using this call in a single threaded ROS application, or any application where the action client's callback queue is not being serviced, will not work. Without a separate thread servicing the queue, or a multi-threaded spinner, there is no way for the client to tell whether or not the server is up because it can't receive a status message. More... | |
~ActionClient () | |
Private Types | |
typedef ActionClient< ActionSpec > | ActionClientT |
typedef boost::function< void(GoalHandle, const FeedbackConstPtr &)> | FeedbackCallback |
typedef boost::function< void(const ActionGoalConstPtr)> | SendGoalFunc |
typedef boost::function< void(GoalHandle)> | TransitionCallback |
Private Member Functions | |
ACTION_DEFINITION (ActionSpec) | |
void | feedbackCb (const ros::MessageEvent< ActionFeedback const > &action_feedback) |
void | initClient (ros::CallbackQueueInterface *queue) |
template<class M > | |
ros::Publisher | queue_advertise (const std::string &topic, uint32_t queue_size, const ros::SubscriberStatusCallback &connect_cb, const ros::SubscriberStatusCallback &disconnect_cb, ros::CallbackQueueInterface *queue) |
template<class M , class T > | |
ros::Subscriber | queue_subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const ros::MessageEvent< M const > &), T *obj, ros::CallbackQueueInterface *queue) |
void | resultCb (const ros::MessageEvent< ActionResult const > &action_result) |
void | sendCancelFunc (const actionlib_msgs::GoalID &cancel_msg) |
void | sendGoalFunc (const ActionGoalConstPtr &action_goal) |
void | statusCb (const ros::MessageEvent< actionlib_msgs::GoalStatusArray const > &status_array_event) |
Full interface to an ActionServer.
ActionClient provides a complete client side implementation of the ActionInterface protocol. It provides callbacks for every client side transition, giving the user full observation into the client side state machine.
Definition at line 59 of file action_client.h.
|
private |
Definition at line 66 of file action_client.h.
|
private |
Definition at line 68 of file action_client.h.
typedef ClientGoalHandle<ActionSpec> actionlib::ActionClient< ActionSpec >::GoalHandle |
Definition at line 62 of file action_client.h.
|
private |
Definition at line 69 of file action_client.h.
|
private |
Definition at line 67 of file action_client.h.
|
inline |
Simple constructor.
Constructs an ActionClient and sets up the necessary ros topics for the ActionInterface
name | The action name. Defines the namespace in which the action communicates |
queue | CallbackQueue from which this action will process messages. The default (NULL) is to use the global queue |
Definition at line 80 of file action_client.h.
|
inline |
Constructor with namespacing options.
Constructs an ActionClient and sets up the necessary ros topics for the ActionInterface, and namespaces them according the a specified NodeHandle
n | The node handle on top of which we want to namespace our action |
name | The action name. Defines the namespace in which the action communicates |
queue | CallbackQueue from which this action will process messages. The default (NULL) is to use the global queue |
Definition at line 97 of file action_client.h.
|
inline |
Definition at line 105 of file action_client.h.
|
private |
|
inline |
Cancel all goals currently running on the action server.
This preempts all goals running on the action server at the point that this message is serviced by the ActionServer.
Definition at line 135 of file action_client.h.
|
inline |
Cancel all goals that were stamped at and before the specified time.
time | All goals stamped at or before time will be canceled |
Definition at line 148 of file action_client.h.
|
inlineprivate |
Definition at line 294 of file action_client.h.
|
inlineprivate |
Definition at line 217 of file action_client.h.
|
inline |
Checks if the action client is successfully connected to the action server.
Definition at line 187 of file action_client.h.
|
inlineprivate |
Definition at line 253 of file action_client.h.
|
inlineprivate |
Definition at line 267 of file action_client.h.
|
inlineprivate |
Definition at line 299 of file action_client.h.
|
inlineprivate |
Definition at line 212 of file action_client.h.
|
inline |
Sends a goal to the ActionServer, and also registers callbacks.
transition_cb | Callback that gets called on every client state transition |
feedback_cb | Callback that gets called whenever feedback for this goal is received |
Definition at line 118 of file action_client.h.
|
inlineprivate |
Definition at line 207 of file action_client.h.
|
inlineprivate |
Definition at line 284 of file action_client.h.
|
inline |
Waits for the ActionServer to connect to this client Often, it can take a second for the action server & client to negotiate a connection, thus, risking the first few goals to be dropped. This call lets the user wait until the network connection to the server is negotiated NOTE: Using this call in a single threaded ROS application, or any application where the action client's callback queue is not being serviced, will not work. Without a separate thread servicing the queue, or a multi-threaded spinner, there is no way for the client to tell whether or not the server is up because it can't receive a status message.
timeout | Max time to block before returning. A zero timeout is interpreted as an infinite timeout. |
Definition at line 169 of file action_client.h.
|
private |
Definition at line 204 of file action_client.h.
|
private |
Definition at line 201 of file action_client.h.
|
private |
Definition at line 199 of file action_client.h.
|
private |
Definition at line 203 of file action_client.h.
|
private |
Definition at line 195 of file action_client.h.
|
private |
Definition at line 196 of file action_client.h.
|
private |
Definition at line 193 of file action_client.h.
|
private |
Definition at line 198 of file action_client.h.
|
private |
Definition at line 205 of file action_client.h.