/usr/include/actionlib/client/action_client.h is in libactionlib-dev 1.11.4-2.
This file is owned by root:root, with mode 0o644.
The actual contents of the file can be viewed below.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 | /*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#ifndef ACTIONLIB_ACTION_CLIENT_H_
#define ACTIONLIB_ACTION_CLIENT_H_
#include <boost/thread/condition.hpp>
#include "ros/ros.h"
#include "ros/callback_queue_interface.h"
#include <actionlib/client/client_helpers.h>
#include <actionlib/client/connection_monitor.h>
#include <actionlib/destruction_guard.h>
namespace actionlib
{
/**
* \brief 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.
*/
template <class ActionSpec>
class ActionClient
{
public:
typedef ClientGoalHandle<ActionSpec> GoalHandle;
private:
ACTION_DEFINITION(ActionSpec);
typedef ActionClient<ActionSpec> ActionClientT;
typedef boost::function<void (GoalHandle) > TransitionCallback;
typedef boost::function<void (GoalHandle, const FeedbackConstPtr&) > FeedbackCallback;
typedef boost::function<void (const ActionGoalConstPtr)> SendGoalFunc;
public:
/**
* \brief Simple constructor
*
* Constructs an ActionClient and sets up the necessary ros topics for the ActionInterface
* \param name The action name. Defines the namespace in which the action communicates
* \param queue CallbackQueue from which this action will process messages.
* The default (NULL) is to use the global queue
*/
ActionClient(const std::string& name, ros::CallbackQueueInterface* queue = NULL)
: n_(name), guard_(new DestructionGuard()),
manager_(guard_)
{
initClient(queue);
}
/**
* \brief 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
* \param n The node handle on top of which we want to namespace our action
* \param name The action name. Defines the namespace in which the action communicates
* \param queue CallbackQueue from which this action will process messages.
* The default (NULL) is to use the global queue
*/
ActionClient(const ros::NodeHandle& n, const std::string& name, ros::CallbackQueueInterface* queue = NULL)
: n_(n, name), guard_(new DestructionGuard()),
manager_(guard_)
{
initClient(queue);
}
~ActionClient()
{
ROS_DEBUG_NAMED("actionlib", "ActionClient: Waiting for destruction guard to clean up");
guard_->destruct();
ROS_DEBUG_NAMED("actionlib", "ActionClient: destruction guard destruct() done");
}
/**
* \brief Sends a goal to the ActionServer, and also registers callbacks
* \param transition_cb Callback that gets called on every client state transition
* \param feedback_cb Callback that gets called whenever feedback for this goal is received
*/
GoalHandle sendGoal(const Goal& goal,
TransitionCallback transition_cb = TransitionCallback(),
FeedbackCallback feedback_cb = FeedbackCallback())
{
ROS_DEBUG_NAMED("actionlib", "about to start initGoal()");
GoalHandle gh = manager_.initGoal(goal, transition_cb, feedback_cb);
ROS_DEBUG_NAMED("actionlib", "Done with initGoal()");
return gh;
}
/**
* \brief 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.
*/
void cancelAllGoals()
{
actionlib_msgs::GoalID cancel_msg;
// CancelAll policy encoded by stamp=0, id=0
cancel_msg.stamp = ros::Time(0,0);
cancel_msg.id = "";
cancel_pub_.publish(cancel_msg);
}
/**
* \brief Cancel all goals that were stamped at and before the specified time
* \param time All goals stamped at or before `time` will be canceled
*/
void cancelGoalsAtAndBeforeTime(const ros::Time& time)
{
actionlib_msgs::GoalID cancel_msg;
cancel_msg.stamp = time;
cancel_msg.id = "";
cancel_pub_.publish(cancel_msg);
}
/**
* \brief 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.
* \param timeout Max time to block before returning. A zero timeout is interpreted as an infinite timeout.
* \return True if the server connected in the allocated time. False on timeout
*/
bool waitForActionServerToStart(const ros::Duration& timeout = ros::Duration(0,0) )
{
if (connection_monitor_)
return connection_monitor_->waitForActionServerToStart(timeout, n_);
else
return false;
}
/**
* @brief Checks if the action client is successfully connected to the action server
* @return True if the server is connected, false otherwise
*/
bool isServerConnected()
{
return connection_monitor_->isServerConnected();
}
private:
ros::NodeHandle n_;
boost::shared_ptr<DestructionGuard> guard_;
GoalManager<ActionSpec> manager_;
ros::Subscriber result_sub_;
ros::Subscriber feedback_sub_;
boost::shared_ptr<ConnectionMonitor> connection_monitor_; // Have to destroy subscribers and publishers before the connection_monitor_, since we call callbacks in the connection_monitor_
ros::Publisher goal_pub_;
ros::Publisher cancel_pub_;
ros::Subscriber status_sub_;
void sendGoalFunc(const ActionGoalConstPtr& action_goal)
{
goal_pub_.publish(action_goal);
}
void sendCancelFunc(const actionlib_msgs::GoalID& cancel_msg)
{
cancel_pub_.publish(cancel_msg);
}
void initClient(ros::CallbackQueueInterface* queue)
{
status_sub_ = queue_subscribe("status", 1, &ActionClientT::statusCb, this, queue);
feedback_sub_ = queue_subscribe("feedback", 1, &ActionClientT::feedbackCb, this, queue);
result_sub_ = queue_subscribe("result", 1, &ActionClientT::resultCb, this, queue);
connection_monitor_.reset(new ConnectionMonitor(feedback_sub_, status_sub_));
// Start publishers and subscribers
goal_pub_ = queue_advertise<ActionGoal>("goal", 10,
boost::bind(&ConnectionMonitor::goalConnectCallback, connection_monitor_, _1),
boost::bind(&ConnectionMonitor::goalDisconnectCallback, connection_monitor_, _1),
queue);
cancel_pub_ = queue_advertise<actionlib_msgs::GoalID>("cancel", 10,
boost::bind(&ConnectionMonitor::cancelConnectCallback, connection_monitor_, _1),
boost::bind(&ConnectionMonitor::cancelDisconnectCallback, connection_monitor_, _1),
queue);
manager_.registerSendGoalFunc(boost::bind(&ActionClientT::sendGoalFunc, this, _1));
manager_.registerCancelFunc(boost::bind(&ActionClientT::sendCancelFunc, this, _1));
}
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)
{
ros::AdvertiseOptions ops;
ops.init<M>(topic, queue_size, connect_cb, disconnect_cb);
ops.tracked_object = ros::VoidPtr();
ops.latch = false;
ops.callback_queue = queue;
return n_.advertise(ops);
}
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)
{
ros::SubscribeOptions ops;
ops.callback_queue = queue;
ops.topic = topic;
ops.queue_size = queue_size;
ops.md5sum = ros::message_traits::md5sum<M>();
ops.datatype = ros::message_traits::datatype<M>();
ops.helper = ros::SubscriptionCallbackHelperPtr(
new ros::SubscriptionCallbackHelperT<const ros::MessageEvent<M const>& >(
boost::bind(fp, obj, _1)
)
);
return n_.subscribe(ops);
}
void statusCb(const ros::MessageEvent<actionlib_msgs::GoalStatusArray const>& status_array_event)
{
ROS_DEBUG_NAMED("actionlib", "Getting status over the wire.");
if (connection_monitor_)
connection_monitor_->processStatus(status_array_event.getConstMessage(), status_array_event.getPublisherName());
manager_.updateStatuses(status_array_event.getConstMessage());
}
void feedbackCb(const ros::MessageEvent<ActionFeedback const>& action_feedback)
{
manager_.updateFeedbacks(action_feedback.getConstMessage());
}
void resultCb(const ros::MessageEvent<ActionResult const>& action_result)
{
manager_.updateResults(action_result.getConstMessage());
}
};
}
#endif
|