Go to the documentation of this file.
35 #ifndef ACTIONLIB__CLIENT__ACTION_CLIENT_H_
36 #define ACTIONLIB__CLIENT__ACTION_CLIENT_H_
42 #include <boost/thread/condition.hpp>
58 template<
class ActionSpec>
62 typedef ClientGoalHandle<ActionSpec>
GoalHandle;
69 typedef boost::function<void (
const ActionGoalConstPtr)>
SendGoalFunc;
81 :
n_(name),
guard_(new DestructionGuard()),
99 :
n_(n, name),
guard_(new DestructionGuard()),
107 ROS_DEBUG_NAMED(
"actionlib",
"ActionClient: Waiting for destruction guard to clean up");
109 ROS_DEBUG_NAMED(
"actionlib",
"ActionClient: destruction guard destruct() done");
137 actionlib_msgs::GoalID cancel_msg;
150 actionlib_msgs::GoalID cancel_msg;
151 cancel_msg.stamp = time;
207 void sendGoalFunc(
const ActionGoalConstPtr & action_goal)
223 n_.
param(
"actionlib_client_pub_queue_size", pub_queue_size, 10);
224 n_.
param(
"actionlib_client_sub_queue_size", sub_queue_size, -1);
225 if (pub_queue_size < 0) {pub_queue_size = 10;}
226 if (sub_queue_size < 0) {sub_queue_size = 0;}
238 goal_pub_ = queue_advertise<ActionGoal>(
"goal",
static_cast<uint32_t
>(pub_queue_size),
243 queue_advertise<actionlib_msgs::GoalID>(
"cancel",
static_cast<uint32_t
>(pub_queue_size),
259 ops.
init<M>(topic, queue_size, connect_cb, disconnect_cb);
266 template<
class M,
class T>
274 ops.
md5sum = ros::message_traits::md5sum<M>();
275 ops.
datatype = ros::message_traits::datatype<M>();
278 boost::bind(fp, obj, boost::placeholders::_1)
308 #endif // ACTIONLIB__CLIENT__ACTION_CLIENT_H_
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)
void cancelConnectCallback(const ros::SingleSubscriberPublisher &pub)
ros::Subscriber result_sub_
void goalConnectCallback(const ros::SingleSubscriberPublisher &pub)
boost::shared_ptr< SubscriptionCallbackHelper > SubscriptionCallbackHelperPtr
boost::shared_ptr< ConnectionMonitor > connection_monitor_
#define ACTION_DEFINITION(ActionSpec)
void feedbackCb(const ros::MessageEvent< ActionFeedback const > &action_feedback)
ActionClient(const std::string &name, ros::CallbackQueueInterface *queue=nullptr)
Simple constructor.
CallbackQueueInterface * callback_queue
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)
CallbackQueueInterface * callback_queue
const std::string & getPublisherName() const
void goalDisconnectCallback(const ros::SingleSubscriberPublisher &pub)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
GoalManager< ActionSpec > manager_
const boost::shared_ptr< ConstMessage > & getConstMessage() const
ActionClient< ActionSpec > ActionClientT
void publish(const boost::shared_ptr< M > &message) const
void sendCancelFunc(const actionlib_msgs::GoalID &cancel_msg)
Publisher advertise(AdvertiseOptions &ops)
void resultCb(const ros::MessageEvent< ActionResult const > &action_result)
void cancelDisconnectCallback(const ros::SingleSubscriberPublisher &pub)
void cancelAllGoals()
Cancel all goals currently running on the action server.
#define ROS_DEBUG_NAMED(name,...)
ros::Subscriber status_sub_
void initClient(ros::CallbackQueueInterface *queue)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void sendGoalFunc(const ActionGoalConstPtr &action_goal)
boost::function< void(GoalHandle)> TransitionCallback
ClientGoalHandle< ActionSpec > GoalHandle
void init(const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback())
void cancelGoalsAtAndBeforeTime(const ros::Time &time)
Cancel all goals that were stamped at and before the specified time.
static bool waitForValid()
bool isServerConnected()
Checks if the action client is successfully connected to the action server.
ros::Subscriber feedback_sub_
T param(const std::string ¶m_name, const T &default_val) const
void statusCb(const ros::MessageEvent< actionlib_msgs::GoalStatusArray const > &status_array_event)
boost::shared_ptr< void > VoidPtr
SubscriptionCallbackHelperPtr helper
VoidConstPtr tracked_object
boost::shared_ptr< DestructionGuard > guard_
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 serve...
GoalHandle sendGoal(const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
Sends a goal to the ActionServer, and also registers callbacks.
boost::function< void(const ActionGoalConstPtr)> SendGoalFunc
ros::Publisher cancel_pub_
boost::function< void(GoalHandle, const FeedbackConstPtr &)> FeedbackCallback
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55