35 #ifndef ACTIONLIB__CLIENT__ACTION_CLIENT_H_ 36 #define ACTIONLIB__CLIENT__ACTION_CLIENT_H_ 42 #include <boost/thread/condition.hpp> 58 template<
class ActionSpec>
107 ROS_DEBUG_NAMED(
"actionlib",
"ActionClient: Waiting for destruction guard to clean up");
109 ROS_DEBUG_NAMED(
"actionlib",
"ActionClient: destruction guard destruct() done");
123 GoalHandle gh =
manager_.initGoal(goal, transition_cb, feedback_cb);
137 actionlib_msgs::GoalID cancel_msg;
150 actionlib_msgs::GoalID cancel_msg;
151 cancel_msg.stamp = time;
209 goal_pub_.
publish(action_goal);
214 cancel_pub_.
publish(cancel_msg);
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 = 1;}
228 status_sub_ =
queue_subscribe(
"status", static_cast<uint32_t>(sub_queue_size),
230 feedback_sub_ =
queue_subscribe(
"feedback", static_cast<uint32_t>(sub_queue_size),
232 result_sub_ =
queue_subscribe(
"result", static_cast<uint32_t>(sub_queue_size),
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, _1)
287 if (connection_monitor_) {
288 connection_monitor_->processStatus(
308 #endif // ACTIONLIB__CLIENT__ACTION_CLIENT_H_ void sendGoalFunc(const ActionGoalConstPtr &action_goal)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void statusCb(const ros::MessageEvent< actionlib_msgs::GoalStatusArray const > &status_array_event)
ros::Publisher cancel_pub_
void cancelGoalsAtAndBeforeTime(const ros::Time &time)
Cancel all goals that were stamped at and before the specified time.
void publish(const boost::shared_ptr< M > &message) const
void goalConnectCallback(const ros::SingleSubscriberPublisher &pub)
bool isServerConnected()
Checks if the action client is successfully connected to the action server.
void init(const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback())
GoalManager< ActionSpec > manager_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber result_sub_
void goalDisconnectCallback(const ros::SingleSubscriberPublisher &pub)
void updateFeedbacks(const ActionFeedbackConstPtr &action_feedback)
ros::Subscriber status_sub_
ClientGoalHandle< ActionSpec > GoalHandle
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 cancelConnectCallback(const ros::SingleSubscriberPublisher &pub)
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...
void updateResults(const ActionResultConstPtr &action_result)
Full interface to an ActionServer.
boost::shared_ptr< SubscriptionCallbackHelper > SubscriptionCallbackHelperPtr
void sendCancelFunc(const actionlib_msgs::GoalID &cancel_msg)
void feedbackCb(const ros::MessageEvent< ActionFeedback const > &action_feedback)
const std::string & getPublisherName() const
GoalHandle sendGoal(const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
Sends a goal to the ActionServer, and also registers callbacks.
#define ROS_DEBUG_NAMED(name,...)
const boost::shared_ptr< ConstMessage > & getConstMessage() const
SubscriptionCallbackHelperPtr helper
VoidConstPtr tracked_object
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 cancelAllGoals()
Cancel all goals currently running on the action server.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void cancelDisconnectCallback(const ros::SingleSubscriberPublisher &pub)
boost::shared_ptr< DestructionGuard > guard_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
This class protects an object from being destructed until all users of that object relinquish control...
#define ACTION_DEFINITION(ActionSpec)
void registerSendGoalFunc(SendGoalFunc send_goal_func)
boost::function< void(const ActionGoalConstPtr)> SendGoalFunc
boost::function< void(GoalHandle)> TransitionCallback
void updateStatuses(const actionlib_msgs::GoalStatusArrayConstPtr &status_array)
Client side handle to monitor goal progress.
ros::Subscriber feedback_sub_
CallbackQueueInterface * callback_queue
void initClient(ros::CallbackQueueInterface *queue)
void registerCancelFunc(CancelFunc cancel_func)
static bool waitForValid()
boost::function< void(GoalHandle, const FeedbackConstPtr &)> FeedbackCallback
boost::shared_ptr< void > VoidPtr
void resultCb(const ros::MessageEvent< ActionResult const > &action_result)
CallbackQueueInterface * callback_queue
boost::shared_ptr< ConnectionMonitor > connection_monitor_
ActionClient(const ros::NodeHandle &n, const std::string &name, ros::CallbackQueueInterface *queue=NULL)
Constructor with namespacing options.