Go to the documentation of this file.
35 #ifndef ACTIONLIB__CLIENT__SIMPLE_ACTION_CLIENT_H_
36 #define ACTIONLIB__CLIENT__SIMPLE_ACTION_CLIENT_H_
38 #include <boost/thread/condition.hpp>
39 #include <boost/thread/mutex.hpp>
40 #include <boost/scoped_ptr.hpp>
41 #include <boost/concept_check.hpp>
54 #define DEPRECATED __attribute__((deprecated))
71 template<
class ActionSpec>
133 return ac_->waitForActionServerToStart(timeout);
142 return ac_->isServerConnected();
244 boost::scoped_ptr<ActionClientT>
ac_;
256 template<
class ActionSpec>
261 ROS_DEBUG_NAMED(
"actionlib",
"Spinning up a thread for the SimpleActionClient");
262 need_to_terminate_ =
false;
267 spin_thread_ =
nullptr;
272 template<
class ActionSpec>
277 boost::mutex::scoped_lock terminate_lock(terminate_mutex_);
278 need_to_terminate_ =
true;
280 spin_thread_->join();
287 template<
class ActionSpec>
292 boost::mutex::scoped_lock terminate_lock(terminate_mutex_);
293 if (need_to_terminate_) {
301 template<
class ActionSpec>
307 template<
class ActionSpec>
310 ROS_DEBUG_NAMED(
"actionlib",
"Transitioning SimpleState from [%s] to [%s]",
311 cur_simple_state_.toString().c_str(),
313 cur_simple_state_ = next_state;
316 template<
class ActionSpec>
327 active_cb_ = active_cb;
328 feedback_cb_ = feedback_cb;
333 gh_ = ac_->sendGoal(goal, boost::bind(&SimpleActionClientT::handleTransition,
this, boost::placeholders::_1),
334 boost::bind(&SimpleActionClientT::handleFeedback,
this, boost::placeholders::_1, boost::placeholders::_2));
337 template<
class ActionSpec>
340 if (gh_.isExpired()) {
344 CommState comm_state_ = gh_.getCommState();
346 switch (comm_state_.
state_) {
356 switch (gh_.getTerminalState().state_) {
359 gh_.getTerminalState().text_);
362 gh_.getTerminalState().text_);
365 gh_.getTerminalState().text_);
368 gh_.getTerminalState().text_);
371 gh_.getTerminalState().text_);
376 "Unknown terminal state [%u]. This is a bug in SimpleActionClient",
377 gh_.getTerminalState().state_);
384 switch (cur_simple_state_.state_) {
391 "In WAITING_FOR_RESULT or WAITING_FOR_CANCEL_ACK, yet we are in SimpleGoalState DONE. This is a bug in SimpleActionClient");
395 "Got a SimpleGoalState of [%u]. This is a bug in SimpleActionClient",
396 cur_simple_state_.state_);
406 template<
class ActionSpec>
410 if (gh_.isExpired()) {
412 "Trying to getResult() when no goal is running. You are incorrectly using SimpleActionClient");
415 if (gh_.getResult()) {
416 return gh_.getResult();
419 return ResultConstPtr(
new Result);
423 template<
class ActionSpec>
426 ac_->cancelAllGoals();
429 template<
class ActionSpec>
432 ac_->cancelGoalsAtAndBeforeTime(time);
435 template<
class ActionSpec>
438 if (gh_.isExpired()) {
440 "Trying to cancelGoal() when no goal is running. You are incorrectly using SimpleActionClient");
446 template<
class ActionSpec>
449 if (gh_.isExpired()) {
451 "Trying to stopTrackingGoal() when no goal is running. You are incorrectly using SimpleActionClient");
456 template<
class ActionSpec>
458 const FeedbackConstPtr & feedback)
462 "Got a callback on a goalHandle that we're not tracking. \
463 This is an internal SimpleActionClient/ActionClient bug. \
464 This could also be a GoalID collision");
467 feedback_cb_(feedback);
471 template<
class ActionSpec>
475 switch (comm_state_.
state_) {
478 "BUG: Shouldn't ever get a transition callback for WAITING_FOR_GOAL_ACK");
482 "BUG: Got a transition to CommState [%s] when our in SimpleGoalState [%s]",
483 comm_state_.
toString().c_str(), cur_simple_state_.toString().c_str());
486 switch (cur_simple_state_.state_) {
497 "BUG: Got a transition to CommState [%s] when in SimpleGoalState [%s]",
498 comm_state_.
toString().c_str(), cur_simple_state_.toString().c_str());
501 ROS_FATAL(
"Unknown SimpleGoalState %u", cur_simple_state_.state_);
511 "BUG: Got a transition to CommState [%s] when our in SimpleGoalState [%s]",
512 comm_state_.
toString().c_str(), cur_simple_state_.toString().c_str());
515 switch (cur_simple_state_.state_) {
526 "BUG: Got a transition to CommState [%s] when in SimpleGoalState [%s]",
527 comm_state_.
toString().c_str(), cur_simple_state_.toString().c_str());
530 ROS_FATAL(
"Unknown SimpleGoalState %u", cur_simple_state_.state_);
535 switch (cur_simple_state_.state_) {
543 boost::mutex::scoped_lock lock(done_mutex_);
547 done_condition_.notify_all();
553 ROS_FATAL(
"Unknown SimpleGoalState %u", cur_simple_state_.state_);
563 template<
class ActionSpec>
566 if (gh_.isExpired()) {
568 "Trying to waitForGoalToFinish() when no goal is running. You are incorrectly using SimpleActionClient");
573 ROS_WARN_NAMED(
"actionlib",
"Timeouts can't be negative. Timeout is [%.2fs]", timeout.
toSec());
578 boost::mutex::scoped_lock lock(done_mutex_);
599 time_left = loop_period;
602 done_condition_.timed_wait(lock,
603 boost::posix_time::milliseconds(
static_cast<int64_t
>(time_left.
toSec() * 1000.0f)));
609 template<
class ActionSpec>
617 if (waitForResult(execute_timeout)) {
618 ROS_DEBUG_NAMED(
"actionlib",
"Goal finished within specified execute_timeout [%.2f]",
619 execute_timeout.
toSec());
623 ROS_DEBUG_NAMED(
"actionlib",
"Goal didn't finish within specified execute_timeout [%.2f]",
624 execute_timeout.
toSec());
630 if (waitForResult(preempt_timeout)) {
631 ROS_DEBUG_NAMED(
"actionlib",
"Preempt finished within specified preempt_timeout [%.2f]",
632 preempt_timeout.
toSec());
634 ROS_DEBUG_NAMED(
"actionlib",
"Preempt didn't finish specified preempt_timeout [%.2f]",
635 preempt_timeout.
toSec());
644 #endif // ACTIONLIB__CLIENT__SIMPLE_ACTION_CLIENT_H_
#define ROS_ERROR_COND(cond,...)
SimpleActionClient(ros::NodeHandle &n, const std::string &name, bool spin_thread=true)
Constructor with namespacing options.
void stopTrackingGoal()
Stops tracking the state of the current goal. Unregisters this goal's callbacks.
Duration & fromSec(double t)
boost::function< void(const SimpleClientGoalState &state, const ResultConstPtr &result)> SimpleDoneCallback
#define ACTION_DEFINITION(ActionSpec)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Waits for the ActionServer to connect to this client.
void handleTransition(GoalHandleT gh)
#define ROS_ERROR_NAMED(name,...)
void initSimpleClient(ros::NodeHandle &n, const std::string &name, bool spin_thread)
SimpleGoalState cur_simple_state_
A Simple client implementation of the ActionInterface which supports only one goal at a time.
Full interface to an ActionServer.
Thin wrapper around an enum in order to help interpret the state of the communication state machine.
std::string toString() const
SimpleClientGoalState sendGoalAndWait(const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
Sends a goal to the ActionServer, and waits until the goal completes or a timeout is exceeded.
boost::function< void()> SimpleActiveCallback
#define ROS_DEBUG_NAMED(name,...)
boost::function< void(const FeedbackConstPtr &feedback)> SimpleFeedbackCallback
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
Sends a goal to the ActionServer, and also registers callbacks.
ResultConstPtr getResult() const
Get the Result of the current goal.
CommState getCommState() const
Get the state of this goal's communication state machine from interaction with the server.
void handleFeedback(GoalHandleT gh, const FeedbackConstPtr &feedback)
void cancelGoalsAtAndBeforeTime(const ros::Time &time)
Cancel all goals that were stamped at and before the specified time.
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
Blocks until this goal finishes.
boost::condition done_condition_
boost::scoped_ptr< ActionClientT > ac_
SimpleDoneCallback done_cb_
bool isServerConnected() const
Checks if the action client is successfully connected to the action server.
boost::thread * spin_thread_
Thin wrapper around an enum in order providing a simplified version of the communication state,...
ros::CallbackQueue callback_queue
void cancelGoal()
Cancel the goal that we are currently pursuing.
ResultConstPtr getResult() const
Get result associated with this goal.
SimpleFeedbackCallback feedback_cb_
#define ROS_WARN_NAMED(name,...)
Client side handle to monitor goal progress.
boost::mutex terminate_mutex_
SimpleClientGoalState getState() const
Get the state information for this goal.
StateEnum
Defines the various states the SimpleGoalState can be in.
void cancelAllGoals()
Cancel all goals currently running on the action server.
std::string toString() const
SimpleActiveCallback active_cb_
void setSimpleState(const SimpleGoalState::StateEnum &next_state)
ActionClient< ActionSpec > ActionClientT
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55