32 import actionlib_msgs.msg
37 * @class ServerGoalHandle
38 * @brief Encapsulates a state machine for a given goal that the user can
39 * trigger transitions on. All ROS interfaces for the goal are managed by
40 * the ActionServer to lessen the burden on the user.
44 def __init__(self, status_tracker=None, action_server=None, handle_tracker=None):
46 A private constructor used by the ActionServer to initialize a ServerGoalHandle.
47 @node The default constructor was not ported.
54 self.
goal = status_tracker.goal
63 Accept the goal referenced by the goal handle. This will
64 transition to the ACTIVE state or the PREEMPTING state depending
65 on whether a cancel request has been received for the goal
68 rospy.logdebug(
"Accepting goal, id: %s, stamp: %.2f", self.
get_goal_id().id, self.
get_goal_id().stamp.to_sec())
74 if status == actionlib_msgs.msg.GoalStatus.PENDING:
75 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.ACTIVE
80 elif status == actionlib_msgs.msg.GoalStatus.RECALLING:
81 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.PREEMPTING
86 rospy.logerr(
"To transition to an active state, the goal must be in a pending or recalling state, it is currently in state: %d", self.
status_tracker.status.status)
89 rospy.logerr(
"Attempt to set status on an uninitialized ServerGoalHandle")
93 Set the status of the goal associated with the ServerGoalHandle to RECALLED or PREEMPTED
94 depending on what the current status of the goal is
95 @param result Optionally, the user can pass in a result to be sent to any clients of the goal
100 rospy.logdebug(
"Setting status to canceled on goal, id: %s, stamp: %.2f", self.
get_goal_id().id, self.
get_goal_id().stamp.to_sec())
105 if status == actionlib_msgs.msg.GoalStatus.PENDING
or status == actionlib_msgs.msg.GoalStatus.RECALLING:
106 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.RECALLED
111 elif status == actionlib_msgs.msg.GoalStatus.ACTIVE
or status == actionlib_msgs.msg.GoalStatus.PREEMPTING:
112 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.PREEMPTED
119 rospy.logerr(
"To transition to a cancelled state, the goal must be in a pending, recalling, active, or preempting state, it is currently in state: %d",
123 rospy.logerr(
"Attempt to set status on an uninitialized ServerGoalHandle")
127 * @brief Set the status of the goal associated with the ServerGoalHandle to rejected
128 * @param result Optionally, the user can pass in a result to be sent to any clients of the goal
133 rospy.logdebug(
"Setting status to rejected on goal, id: %s, stamp: %.2f", self.
get_goal_id().id, self.
get_goal_id().stamp.to_sec())
137 if status == actionlib_msgs.msg.GoalStatus.PENDING
or status == actionlib_msgs.msg.GoalStatus.RECALLING:
138 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.REJECTED
145 rospy.logerr(
"To transition to a rejected state, the goal must be in a pending or recalling state, it is currently in state: %d",
149 rospy.logerr(
"Attempt to set status on an uninitialized ServerGoalHandle")
153 Set the status of the goal associated with the ServerGoalHandle to aborted
154 @param result Optionally, the user can pass in a result to be sent to any clients of the goal
159 rospy.logdebug(
"Setting status to aborted on goal, id: %s, stamp: %.2f", self.
get_goal_id().id, self.
get_goal_id().stamp.to_sec())
163 if status == actionlib_msgs.msg.GoalStatus.PREEMPTING
or status == actionlib_msgs.msg.GoalStatus.ACTIVE:
164 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.ABORTED
171 rospy.logerr(
"To transition to an aborted state, the goal must be in a preempting or active state, it is currently in state: %d",
175 rospy.logerr(
"Attempt to set status on an uninitialized ServerGoalHandle")
179 Set the status of the goal associated with the ServerGoalHandle to succeeded
180 @param result Optionally, the user can pass in a result to be sent to any clients of the goal
185 rospy.logdebug(
"Setting status to succeeded on goal, id: %s, stamp: %.2f",
190 if status == actionlib_msgs.msg.GoalStatus.PREEMPTING
or status == actionlib_msgs.msg.GoalStatus.ACTIVE:
191 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.SUCCEEDED
198 rospy.logerr(
"To transition to a succeeded state, the goal must be in a preempting or active state, it is currently in state: %d",
202 rospy.logerr(
"Attempt to set status on an uninitialized ServerGoalHandle")
206 Send feedback to any clients of the goal associated with this ServerGoalHandle
207 @param feedback The feedback to send to the client
209 rospy.logdebug(
"Publishing feedback for goal, id: %s, stamp: %.2f",
215 rospy.logerr(
"Attempt to publish feedback on an uninitialized ServerGoalHandle")
219 Accessor for the goal associated with the ServerGoalHandle
220 @return A shared_ptr to the goal object
228 return self.
goal.goal
234 Accessor for the goal id associated with the ServerGoalHandle
241 rospy.logerr(
"Attempt to get a goal id on an uninitialized ServerGoalHandle")
242 return actionlib_msgs.msg.GoalID()
246 Accessor for the status associated with the ServerGoalHandle
247 @return The goal status
253 rospy.logerr(
"Attempt to get goal status on an uninitialized ServerGoalHandle")
254 return actionlib_msgs.msg.GoalStatus()
258 Equals operator for ServerGoalHandles
259 @param other The ServerGoalHandle to compare to
260 @return True if the ServerGoalHandles refer to the same goal, false otherwise
263 if not self.
goal or not other.goal:
266 their_id = other.get_goal_id()
267 return my_id.id == their_id.id
271 != operator for ServerGoalHandles
272 @param other The ServerGoalHandle to compare to
273 @return True if the ServerGoalHandles refer to different goals, false otherwise
275 if not self.
goal or not other.goal:
278 their_id = other.get_goal_id()
280 return my_id.id != their_id.id
284 hash function for ServerGoalHandles
285 @return hash of the goal ID
291 A private method to set status to PENDING or RECALLING
292 @return True if the cancel request should be passed on to the user, false otherwise
294 rospy.logdebug(
"Transisitoning to a cancel requested state on goal id: %s, stamp: %.2f",
299 if status == actionlib_msgs.msg.GoalStatus.PENDING:
300 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.RECALLING
304 if status == actionlib_msgs.msg.GoalStatus.ACTIVE:
305 self.
status_tracker.status.status = actionlib_msgs.msg.GoalStatus.PREEMPTING