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>
61 typename ManagedListT::Handle handle,
66 list_handle_ = handle;
70 template<
class ActionSpec>
74 DestructionGuard::ScopedProtector protector(*guard_);
75 if (!protector.isProtected()) {
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");
112 if (!protector.isProtected()) {
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");
131 if (!protector.isProtected()) {
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]",
148 comm_state_.toString().c_str());
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");
192 return typename ClientGoalHandle<ActionSpec>::ResultConstPtr() ;
195 DestructionGuard::ScopedProtector protector(*guard_);
196 if (!protector.isProtected()) {
198 "This action client associated with the goal handle has already been destructed. Ignoring this getResult() call");
199 return typename ClientGoalHandle<ActionSpec>::ResultConstPtr();
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");
215 if (!protector.isProtected()) {
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");
257 DestructionGuard::ScopedProtector protector(*guard_);
258 if (!protector.isProtected()) {
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_) {
311 DestructionGuard::ScopedProtector protector(*guard_);
312 if (!protector.isProtected()) {
314 "This action client associated with the goal handle has already been destructed. Ignoring this operator==() call");
318 return list_handle_ == rhs.list_handle_;
321 template<
class ActionSpec>
324 return !(*
this == rhs);
329 #endif // ACTIONLIB__CLIENT__CLIENT_GOAL_HANDLE_IMP_H_