@@ -37,6 +37,7 @@ def __init__(self):
37
37
self .initial_pose_pub = self .create_publisher (PoseWithCovarianceStamped ,
38
38
'initialpose' , 10 )
39
39
self .initial_pose_received = False
40
+ self .goal_handle = None
40
41
41
42
pose_qos = QoSProfile (
42
43
durability = QoSDurabilityPolicy .RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL ,
@@ -71,7 +72,7 @@ def setWaypoints(self, waypoints):
71
72
msg .pose .orientation .w = 1.0
72
73
self .waypoints .append (msg )
73
74
74
- def run (self ):
75
+ def run (self , block ):
75
76
if not self .waypoints :
76
77
rclpy .error_msg ('Did not set valid waypoints before running test!' )
77
78
return False
@@ -86,16 +87,19 @@ def run(self):
86
87
send_goal_future = self .action_client .send_goal_async (action_request )
87
88
try :
88
89
rclpy .spin_until_future_complete (self , send_goal_future )
89
- goal_handle = send_goal_future .result ()
90
+ self . goal_handle = send_goal_future .result ()
90
91
except Exception as e :
91
92
self .error_msg ('Service call failed %r' % (e ,))
92
93
93
- if not goal_handle .accepted :
94
+ if not self . goal_handle .accepted :
94
95
self .error_msg ('Goal rejected' )
95
96
return False
96
97
97
98
self .info_msg ('Goal accepted' )
98
- get_result_future = goal_handle .get_result_async ()
99
+ if not block :
100
+ return True
101
+
102
+ get_result_future = self .goal_handle .get_result_async ()
99
103
100
104
self .info_msg ("Waiting for 'FollowWaypoints' action to complete" )
101
105
try :
@@ -148,14 +152,18 @@ def shutdown(self):
148
152
except Exception as e :
149
153
self .error_msg ('Service call failed %r' % (e ,))
150
154
155
+ def cancel_goal (self ):
156
+ cancel_future = self .goal_handle .cancel_goal_async ()
157
+ rclpy .spin_until_future_complete (self , cancel_future )
158
+
151
159
def info_msg (self , msg : str ):
152
- self .get_logger ().info (' \033 [1;37;44m' + msg + ' \033 [0m' )
160
+ self .get_logger ().info (msg )
153
161
154
162
def warn_msg (self , msg : str ):
155
- self .get_logger ().warn (' \033 [1;37;43m' + msg + ' \033 [0m' )
163
+ self .get_logger ().warn (msg )
156
164
157
165
def error_msg (self , msg : str ):
158
- self .get_logger ().error (' \033 [1;37;41m' + msg + ' \033 [0m' )
166
+ self .get_logger ().error (msg )
159
167
160
168
161
169
def main (argv = sys .argv [1 :]):
@@ -179,7 +187,19 @@ def main(argv=sys.argv[1:]):
179
187
test .info_msg ('Waiting for amcl_pose to be received' )
180
188
rclpy .spin_once (test , timeout_sec = 1.0 ) # wait for poseCallback
181
189
182
- result = test .run ()
190
+ result = test .run (True )
191
+
192
+ # preempt with new point
193
+ test .setWaypoints ([starting_pose ])
194
+ result = test .run (False )
195
+ time .sleep (2 )
196
+ test .setWaypoints ([wps [1 ]])
197
+ result = test .run (False )
198
+
199
+ # cancel
200
+ time .sleep (2 )
201
+ test .cancel_goal ()
202
+
183
203
test .shutdown ()
184
204
test .info_msg ('Done Shutting Down.' )
185
205
0 commit comments