38 #ifndef ACTIONLIB__CLIENT__CLIENT_GOAL_HANDLE_IMP_H_ 39 #define ACTIONLIB__CLIENT__CLIENT_GOAL_HANDLE_IMP_H_ 46 template<
class ActionSpec>
53 template<
class ActionSpec>
59 template<
class ActionSpec>
66 list_handle_ = handle;
70 template<
class ActionSpec>
77 "This action client associated with the goal handle has already been destructed. Ignoring this reset() call");
81 boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
88 template<
class ActionSpec>
95 template<
class ActionSpec>
104 boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
107 "Trying to getCommState on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
114 "This action client associated with the goal handle has already been destructed. Ignoring this getCommState() call");
118 return list_handle_.getElem()->getCommState();
121 template<
class ActionSpec>
126 "Trying to getTerminalState on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
133 "This action client associated with the goal handle has already been destructed. Ignoring this getTerminalState() call");
144 boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
145 CommState comm_state_ = list_handle_.getElem()->getCommState();
147 ROS_WARN_NAMED(
"actionlib",
"Asking for the terminal state when we're in [%s]",
151 actionlib_msgs::GoalStatus goal_status = list_handle_.getElem()->getGoalStatus();
153 switch (goal_status.status) {
154 case actionlib_msgs::GoalStatus::PENDING:
155 case actionlib_msgs::GoalStatus::ACTIVE:
156 case actionlib_msgs::GoalStatus::PREEMPTING:
157 case actionlib_msgs::GoalStatus::RECALLING:
158 ROS_ERROR_NAMED(
"actionlib",
"Asking for terminal state, but latest goal status is %u",
174 ROS_ERROR_NAMED(
"actionlib",
"Unknown goal status: %u", goal_status.status);
break;
181 template<
class ActionSpec>
187 "Trying to getResult on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
198 "This action client associated with the goal handle has already been destructed. Ignoring this getResult() call");
202 boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
203 return list_handle_.getElem()->getResult();
206 template<
class ActionSpec>
211 "Trying to resend() on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
217 "This action client associated with the goal handle has already been destructed. Ignoring this resend() call");
228 boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
230 ActionGoalConstPtr action_goal = list_handle_.getElem()->getActionGoal();
236 if (gm_->send_goal_func_) {
237 gm_->send_goal_func_(action_goal);
241 template<
class ActionSpec>
246 "Trying to cancel() on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
260 "This action client associated with the goal handle has already been destructed. Ignoring this call");
264 boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
266 switch (list_handle_.getElem()->getCommState().state_) {
276 ROS_DEBUG_NAMED(
"actionlib",
"Got a cancel() request while in state [%s], so ignoring it",
277 list_handle_.getElem()->getCommState().toString().c_str());
281 list_handle_.getElem()->getCommState().state_);
285 ActionGoalConstPtr action_goal = list_handle_.getElem()->getActionGoal();
287 actionlib_msgs::GoalID cancel_msg;
289 cancel_msg.id = list_handle_.getElem()->getActionGoal()->goal_id.id;
291 if (gm_->cancel_func_) {
292 gm_->cancel_func_(cancel_msg);
298 template<
class ActionSpec>
302 if (!active_ && !rhs.
active_) {
307 if (!active_ || !rhs.
active_) {
314 "This action client associated with the goal handle has already been destructed. Ignoring this operator==() call");
321 template<
class ActionSpec>
324 return !(*
this == rhs);
329 #endif // ACTIONLIB__CLIENT__CLIENT_GOAL_HANDLE_IMP_H_
std::string toString() const
ClientGoalHandle()
Create an empty goal handle.
ManagedListT::Handle list_handle_
#define ROS_WARN_NAMED(name,...)
void resend()
Resends this goal [with the same GoalID] to the ActionServer.
bool isProtected()
Checks if the ScopedProtector successfully protected the DestructionGuard.
#define ROS_DEBUG_NAMED(name,...)
Thin wrapper around an enum in order to help interpret the state of the communication state machine...
bool operator==(const ClientGoalHandle< ActionSpec > &rhs) const
Check if two goal handles point to the same goal.
CommState getCommState() const
Get the state of this goal's communication state machine from interaction with the server...
bool isExpired() const
Checks if this goal handle is tracking a goal.
ResultConstPtr getResult() const
Get result associated with this goal.
void reset()
Stops goal handle from tracking a goal.
#define ROS_ERROR_NAMED(name,...)
void cancel()
Sends a cancel message for this specific goal to the ActionServer.
bool operator!=(const ClientGoalHandle< ActionSpec > &rhs) const
!(operator==())
Client side handle to monitor goal progress.
Protects a DestructionGuard until this object goes out of scope.
TerminalState getTerminalState() const
Get the terminal state information for this goal.