@@ -64,7 +64,6 @@ def __init__(self):
64
64
65
65
self .desired_vel = 0.3
66
66
self .y_int = 0.0
67
-
68
67
69
68
def declare_los_parameters_ (self ):
70
69
"""Declare all LOS guidance parameters."""
@@ -133,7 +132,6 @@ def _declare_topic_parameters(self):
133
132
134
133
def _initialize_publishers (self ):
135
134
"""Initialize all publishers."""
136
-
137
135
los_commands_topic = self .get_parameter ('topics.publishers.los_commands' ).value
138
136
self .get_logger ().info (f"Publishing LOS commands to: { los_commands_topic } " )
139
137
self .guidance_cmd_pub = self .create_publisher (
@@ -219,7 +217,10 @@ def odom_callback(self, msg: Odometry):
219
217
self .filter_initialized = True
220
218
221
219
def calculate_guidance (self ) -> State :
222
- error = self .state .as_pos_array () - self .waypoints [self .current_waypoint_index ].as_pos_array ()
220
+ error = (
221
+ self .state .as_pos_array ()
222
+ - self .waypoints [self .current_waypoint_index ].as_pos_array ()
223
+ )
223
224
_ , crosstrack_y , crosstrack_z = self .rotation_yz @ error
224
225
alpha_c = self .guidance_calculator .calculate_alpha_c (
225
226
self .u , self .v , self .w , self .phi
@@ -233,8 +234,12 @@ def calculate_guidance(self) -> State:
233
234
crosstrack_y ,
234
235
self .y_int ,
235
236
)
236
- y_int_dot = self .guidance_calculator .calculate_y_int_dot (crosstrack_y , self .y_int )
237
- self .y_int += y_int_dot * self .update_period # Forward euler, may need to use Runge-Kutta 4
237
+ y_int_dot = self .guidance_calculator .calculate_y_int_dot (
238
+ crosstrack_y , self .y_int
239
+ )
240
+ self .y_int += (
241
+ y_int_dot * self .update_period
242
+ ) # Forward euler, may need to use Runge-Kutta 4
238
243
theta_d = self .guidance_calculator .compute_theta_d (
239
244
self .waypoints [self .current_waypoint_index ],
240
245
self .waypoints [self .current_waypoint_index + 1 ],
@@ -254,7 +259,6 @@ def calculate_guidance(self) -> State:
254
259
255
260
def execute_callback (self , goal_handle : ServerGoalHandle ):
256
261
"""Execute waypoint navigation action."""
257
-
258
262
# Initialize navigation goal with lock
259
263
with self ._goal_lock :
260
264
self .goal_handle = goal_handle
@@ -269,15 +273,24 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
269
273
)
270
274
self .waypoints .append (point_as_state )
271
275
272
- self .pi_h = self .guidance_calculator .compute_pi_h (self .waypoints [self .current_waypoint_index ], self .waypoints [self .current_waypoint_index + 1 ])
273
- self .pi_v = self .guidance_calculator .compute_pi_v (self .waypoints [self .current_waypoint_index ], self .waypoints [self .current_waypoint_index + 1 ])
276
+ self .pi_h = self .guidance_calculator .compute_pi_h (
277
+ self .waypoints [self .current_waypoint_index ],
278
+ self .waypoints [self .current_waypoint_index + 1 ],
279
+ )
280
+ self .pi_v = self .guidance_calculator .compute_pi_v (
281
+ self .waypoints [self .current_waypoint_index ],
282
+ self .waypoints [self .current_waypoint_index + 1 ],
283
+ )
274
284
275
285
rotation_y = self .guidance_calculator .compute_rotation_y (self .pi_v )
276
286
rotation_z = self .guidance_calculator .compute_rotation_z (self .pi_h )
277
287
self .rotation_yz = rotation_y .T @ rotation_z .T
278
288
279
289
# Initialize y_int based on initial crosstrack error
280
- initial_error = self .state .as_pos_array () - self .waypoints [self .current_waypoint_index ].as_pos_array ()
290
+ initial_error = (
291
+ self .state .as_pos_array ()
292
+ - self .waypoints [self .current_waypoint_index ].as_pos_array ()
293
+ )
281
294
_ , initial_crosstrack_y , _ = self .rotation_yz @ initial_error
282
295
self .y_int = - initial_crosstrack_y / self .guidance_calculator .kappa
283
296
@@ -286,7 +299,9 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
286
299
287
300
rate = self .create_rate (1.0 / self .update_period )
288
301
waiting_at_waypoint = False
289
- wait_cycles = int (1.0 / self .update_period ) # Number of cycles for 1 second wait
302
+ wait_cycles = int (
303
+ 1.0 / self .update_period
304
+ ) # Number of cycles for 1 second wait
290
305
wait_count = 0
291
306
292
307
self .get_logger ().info ('Executing goal' )
@@ -314,39 +329,53 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
314
329
if not waiting_at_waypoint :
315
330
self .get_logger ().info ('Waypoint reached' )
316
331
waiting_at_waypoint = True
317
- stop_state = State (surge_vel = 0.0 , pitch = self .state .pitch , yaw = self .state .yaw )
332
+ stop_state = State (
333
+ surge_vel = 0.0 , pitch = self .state .pitch , yaw = self .state .yaw
334
+ )
318
335
self .guidance_calculator .reset_filter_state (stop_state )
319
336
320
337
if wait_count < wait_cycles :
321
- self .publish_guidance (State (surge_vel = 0.0 , pitch = self .state .pitch , yaw = self .state .yaw ))
338
+ self .publish_guidance (
339
+ State (surge_vel = 0.0 , pitch = self .state .pitch , yaw = self .state .yaw )
340
+ )
322
341
wait_count += 1
323
342
else :
324
343
self .current_waypoint_index += 1
325
344
# Reset integral term for new waypoint
326
- initial_error = self .state .as_pos_array () - self .waypoints [self .current_waypoint_index ].as_pos_array ()
345
+ initial_error = (
346
+ self .state .as_pos_array ()
347
+ - self .waypoints [self .current_waypoint_index ].as_pos_array ()
348
+ )
327
349
_ , initial_crosstrack_y , _ = self .rotation_yz @ initial_error
328
350
self .y_int = - initial_crosstrack_y / self .guidance_calculator .kappa
329
351
waiting_at_waypoint = False
330
352
wait_count = 0
331
-
353
+
332
354
# Reset filter with stop state
333
355
# self.guidance_calculator.reset_filter_state(stop_state)
334
-
356
+
335
357
# # Publish stop command and wait briefly
336
358
# self.publish_guidance(stop_state)
337
359
# time.sleep(2.0) # Wait for 2 seconds to stabilize
338
-
339
360
340
361
if self .current_waypoint_index >= len (self .waypoints ) - 1 :
341
362
self .get_logger ().info ('All waypoints reached!' )
342
- final_commands = State (surge_vel = 0.0 , pitch = self .state .pitch , yaw = self .state .yaw )
363
+ final_commands = State (
364
+ surge_vel = 0.0 , pitch = self .state .pitch , yaw = self .state .yaw
365
+ )
343
366
self .publish_guidance (final_commands )
344
367
result .success = True
345
368
self .goal_handle .succeed ()
346
369
return result
347
-
348
- self .pi_h = self .guidance_calculator .compute_pi_h (self .waypoints [self .current_waypoint_index ], self .waypoints [self .current_waypoint_index + 1 ])
349
- self .pi_v = self .guidance_calculator .compute_pi_v (self .waypoints [self .current_waypoint_index ], self .waypoints [self .current_waypoint_index + 1 ])
370
+
371
+ self .pi_h = self .guidance_calculator .compute_pi_h (
372
+ self .waypoints [self .current_waypoint_index ],
373
+ self .waypoints [self .current_waypoint_index + 1 ],
374
+ )
375
+ self .pi_v = self .guidance_calculator .compute_pi_v (
376
+ self .waypoints [self .current_waypoint_index ],
377
+ self .waypoints [self .current_waypoint_index + 1 ],
378
+ )
350
379
351
380
rotation_y = self .guidance_calculator .compute_rotation_y (self .pi_v )
352
381
rotation_z = self .guidance_calculator .compute_rotation_z (self .pi_h )
@@ -366,6 +395,7 @@ def publish_guidance(self, commands: State):
366
395
msg .yaw = commands .yaw
367
396
self .guidance_cmd_pub .publish (msg )
368
397
398
+
369
399
def main (args = None ):
370
400
"""Main function to initialize and run the guidance node."""
371
401
rclpy .init (args = args )
@@ -384,4 +414,4 @@ def main(args=None):
384
414
385
415
386
416
if __name__ == '__main__' :
387
- main ()
417
+ main ()
0 commit comments