client_goal_handle_imp.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* This file has the template implementation for ClientGoalHandle. It should be included with the
36  * class definition.
37  */
38 #ifndef ACTIONLIB__CLIENT__CLIENT_GOAL_HANDLE_IMP_H_
39 #define ACTIONLIB__CLIENT__CLIENT_GOAL_HANDLE_IMP_H_
40 
41 #include <ros/ros.h>
42 
43 namespace actionlib
44 {
45 
46 template<class ActionSpec>
48 {
49  gm_ = NULL;
50  active_ = false;
51 }
52 
53 template<class ActionSpec>
55 {
56  reset();
57 }
58 
59 template<class ActionSpec>
61  typename ManagedListT::Handle handle,
63 {
64  gm_ = gm;
65  active_ = true;
66  list_handle_ = handle;
67  guard_ = guard;
68 }
69 
70 template<class ActionSpec>
72 {
73  if (active_) {
74  DestructionGuard::ScopedProtector protector(*guard_);
75  if (!protector.isProtected()) {
76  ROS_ERROR_NAMED("actionlib",
77  "This action client associated with the goal handle has already been destructed. Ignoring this reset() call");
78  return;
79  }
80 
81  boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
82  list_handle_.reset();
83  active_ = false;
84  gm_ = NULL;
85  }
86 }
87 
88 template<class ActionSpec>
90 {
91  return !active_;
92 }
93 
94 
95 template<class ActionSpec>
97 {
98  assert(gm_);
99  if (!gm_) {
100  ROS_ERROR_NAMED("actionlib", "Client should have valid GoalManager");
101  return CommState(CommState::DONE);
102  }
103 
104  boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
105  if (!active_) {
106  ROS_ERROR_NAMED("actionlib",
107  "Trying to getCommState on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
108  return CommState(CommState::DONE);
109  }
110 
111  DestructionGuard::ScopedProtector protector(*guard_);
112  if (!protector.isProtected()) {
113  ROS_ERROR_NAMED("actionlib",
114  "This action client associated with the goal handle has already been destructed. Ignoring this getCommState() call");
115  return CommState(CommState::DONE);
116  }
117 
118  return list_handle_.getElem()->getCommState();
119 }
120 
121 template<class ActionSpec>
123 {
124  if (!active_) {
125  ROS_ERROR_NAMED("actionlib",
126  "Trying to getTerminalState on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
128  }
129 
130  DestructionGuard::ScopedProtector protector(*guard_);
131  if (!protector.isProtected()) {
132  ROS_ERROR_NAMED("actionlib",
133  "This action client associated with the goal handle has already been destructed. Ignoring this getTerminalState() call");
135  }
136 
137  assert(gm_);
138  if (!gm_)
139  {
140  ROS_ERROR_NAMED("actionlib", "Client should have valid GoalManager");
142  }
143 
144  boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
145  CommState comm_state_ = list_handle_.getElem()->getCommState();
146  if (comm_state_ != CommState::DONE) {
147  ROS_WARN_NAMED("actionlib", "Asking for the terminal state when we're in [%s]",
148  comm_state_.toString().c_str());
149  }
150 
151  actionlib_msgs::GoalStatus goal_status = list_handle_.getElem()->getGoalStatus();
152 
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",
159  goal_status.status); return TerminalState(TerminalState::LOST,
160  goal_status.text);
161  case actionlib_msgs::GoalStatus::PREEMPTED: return TerminalState(TerminalState::PREEMPTED,
162  goal_status.text);
163  case actionlib_msgs::GoalStatus::SUCCEEDED: return TerminalState(TerminalState::SUCCEEDED,
164  goal_status.text);
165  case actionlib_msgs::GoalStatus::ABORTED: return TerminalState(TerminalState::ABORTED,
166  goal_status.text);
167  case actionlib_msgs::GoalStatus::REJECTED: return TerminalState(TerminalState::REJECTED,
168  goal_status.text);
169  case actionlib_msgs::GoalStatus::RECALLED: return TerminalState(TerminalState::RECALLED,
170  goal_status.text);
171  case actionlib_msgs::GoalStatus::LOST: return TerminalState(TerminalState::LOST,
172  goal_status.text);
173  default:
174  ROS_ERROR_NAMED("actionlib", "Unknown goal status: %u", goal_status.status); break;
175  }
176 
177  ROS_ERROR_NAMED("actionlib", "Bug in determining terminal state");
178  return TerminalState(TerminalState::LOST, goal_status.text);
179 }
180 
181 template<class ActionSpec>
183 const
184 {
185  if (!active_) {
186  ROS_ERROR_NAMED("actionlib",
187  "Trying to getResult on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
188  }
189  assert(gm_);
190  if (!gm_) {
191  ROS_ERROR_NAMED("actionlib", "Client should have valid GoalManager");
193  }
194 
195  DestructionGuard::ScopedProtector protector(*guard_);
196  if (!protector.isProtected()) {
197  ROS_ERROR_NAMED("actionlib",
198  "This action client associated with the goal handle has already been destructed. Ignoring this getResult() call");
200  }
201 
202  boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
203  return list_handle_.getElem()->getResult();
204 }
205 
206 template<class ActionSpec>
208 {
209  if (!active_) {
210  ROS_ERROR_NAMED("actionlib",
211  "Trying to resend() on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
212  }
213 
214  DestructionGuard::ScopedProtector protector(*guard_);
215  if (!protector.isProtected()) {
216  ROS_ERROR_NAMED("actionlib",
217  "This action client associated with the goal handle has already been destructed. Ignoring this resend() call");
218  return;
219  }
220 
221  assert(gm_);
222  if (!gm_)
223  {
224  ROS_ERROR_NAMED("actionlib", "Client should have valid GoalManager");
225  return;
226  }
227 
228  boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
229 
230  ActionGoalConstPtr action_goal = list_handle_.getElem()->getActionGoal();
231 
232  if (!action_goal) {
233  ROS_ERROR_NAMED("actionlib", "BUG: Got a NULL action_goal");
234  }
235 
236  if (gm_->send_goal_func_) {
237  gm_->send_goal_func_(action_goal);
238  }
239 }
240 
241 template<class ActionSpec>
243 {
244  if (!active_) {
245  ROS_ERROR_NAMED("actionlib",
246  "Trying to cancel() on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
247  return;
248  }
249 
250  assert(gm_);
251  if (!gm_)
252  {
253  ROS_ERROR_NAMED("actionlib", "Client should have valid GoalManager");
254  return;
255  }
256 
257  DestructionGuard::ScopedProtector protector(*guard_);
258  if (!protector.isProtected()) {
259  ROS_ERROR_NAMED("actionlib",
260  "This action client associated with the goal handle has already been destructed. Ignoring this call");
261  return;
262  }
263 
264  boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
265 
266  switch (list_handle_.getElem()->getCommState().state_) {
268  case CommState::PENDING:
269  case CommState::ACTIVE:
271  break; // Continue standard processing
275  case CommState::DONE:
276  ROS_DEBUG_NAMED("actionlib", "Got a cancel() request while in state [%s], so ignoring it",
277  list_handle_.getElem()->getCommState().toString().c_str());
278  return;
279  default:
280  ROS_ERROR_NAMED("actionlib", "BUG: Unhandled CommState: %u",
281  list_handle_.getElem()->getCommState().state_);
282  return;
283  }
284 
285  ActionGoalConstPtr action_goal = list_handle_.getElem()->getActionGoal();
286 
287  actionlib_msgs::GoalID cancel_msg;
288  cancel_msg.stamp = ros::Time(0, 0);
289  cancel_msg.id = list_handle_.getElem()->getActionGoal()->goal_id.id;
290 
291  if (gm_->cancel_func_) {
292  gm_->cancel_func_(cancel_msg);
293  }
294 
295  list_handle_.getElem()->transitionToState(*this, CommState::WAITING_FOR_CANCEL_ACK);
296 }
297 
298 template<class ActionSpec>
300 {
301  // Check if both are inactive
302  if (!active_ && !rhs.active_) {
303  return true;
304  }
305 
306  // Check if one or the other is inactive
307  if (!active_ || !rhs.active_) {
308  return false;
309  }
310 
311  DestructionGuard::ScopedProtector protector(*guard_);
312  if (!protector.isProtected()) {
313  ROS_ERROR_NAMED("actionlib",
314  "This action client associated with the goal handle has already been destructed. Ignoring this operator==() call");
315  return false;
316  }
317 
318  return list_handle_ == rhs.list_handle_;
319 }
320 
321 template<class ActionSpec>
323 {
324  return !(*this == rhs);
325 }
326 
327 } // namespace actionlib
328 
329 #endif // ACTIONLIB__CLIENT__CLIENT_GOAL_HANDLE_IMP_H_
ClientGoalHandle()
Create an empty goal handle.
ManagedListT::Handle list_handle_
bool operator!=(const ClientGoalHandle< ActionSpec > &rhs) const
!(operator==())
#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,...)
std::string toString() const
Definition: comm_state.h:86
Thin wrapper around an enum in order to help interpret the state of the communication state machine...
Definition: comm_state.h:47
bool isExpired() const
Checks if this goal handle is tracking a goal.
CommState getCommState() const
Get the state of this goal&#39;s communication state machine from interaction with the server...
void reset()
Stops goal handle from tracking a goal.
TerminalState getTerminalState() const
Get the terminal state information for this goal.
#define ROS_ERROR_NAMED(name,...)
void cancel()
Sends a cancel message for this specific goal to the ActionServer.
Client side handle to monitor goal progress.
bool operator==(const ClientGoalHandle< ActionSpec > &rhs) const
Check if two goal handles point to the same goal.
Protects a DestructionGuard until this object goes out of scope.
ResultConstPtr getResult() const
Get result associated with this goal.


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 18 2019 03:59:59