@@ -64,7 +64,6 @@ def __init__(self):
6464
6565        self .desired_vel  =  0.3 
6666        self .y_int  =  0.0 
67-         
6867
6968    def  declare_los_parameters_ (self ):
7069        """Declare all LOS guidance parameters.""" 
@@ -133,7 +132,6 @@ def _declare_topic_parameters(self):
133132
134133    def  _initialize_publishers (self ):
135134        """Initialize all publishers.""" 
136- 
137135        los_commands_topic  =  self .get_parameter ('topics.publishers.los_commands' ).value 
138136        self .get_logger ().info (f"Publishing LOS commands to: { los_commands_topic }  )
139137        self .guidance_cmd_pub  =  self .create_publisher (
@@ -219,7 +217,10 @@ def odom_callback(self, msg: Odometry):
219217            self .filter_initialized  =  True 
220218
221219    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+         )
223224        _ , crosstrack_y , crosstrack_z  =  self .rotation_yz  @ error 
224225        alpha_c  =  self .guidance_calculator .calculate_alpha_c (
225226            self .u , self .v , self .w , self .phi 
@@ -233,8 +234,12 @@ def calculate_guidance(self) -> State:
233234            crosstrack_y ,
234235            self .y_int ,
235236        )
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 
238243        theta_d  =  self .guidance_calculator .compute_theta_d (
239244            self .waypoints [self .current_waypoint_index ],
240245            self .waypoints [self .current_waypoint_index  +  1 ],
@@ -254,7 +259,6 @@ def calculate_guidance(self) -> State:
254259
255260    def  execute_callback (self , goal_handle : ServerGoalHandle ):
256261        """Execute waypoint navigation action.""" 
257- 
258262        # Initialize navigation goal with lock 
259263        with  self ._goal_lock :
260264            self .goal_handle  =  goal_handle 
@@ -269,15 +273,24 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
269273            )
270274            self .waypoints .append (point_as_state )
271275
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+         )
274284
275285        rotation_y  =  self .guidance_calculator .compute_rotation_y (self .pi_v )
276286        rotation_z  =  self .guidance_calculator .compute_rotation_z (self .pi_h )
277287        self .rotation_yz  =  rotation_y .T  @ rotation_z .T 
278288
279289        # 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+         )
281294        _ , initial_crosstrack_y , _  =  self .rotation_yz  @ initial_error 
282295        self .y_int  =  - initial_crosstrack_y  /  self .guidance_calculator .kappa 
283296
@@ -286,7 +299,9 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
286299
287300        rate  =  self .create_rate (1.0  /  self .update_period )
288301        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 
290305        wait_count  =  0 
291306
292307        self .get_logger ().info ('Executing goal' )
@@ -314,39 +329,53 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
314329                if  not  waiting_at_waypoint :
315330                    self .get_logger ().info ('Waypoint reached' )
316331                    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+                     )
318335                    self .guidance_calculator .reset_filter_state (stop_state )
319336
320337                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+                     )
322341                    wait_count  +=  1 
323342                else :
324343                    self .current_waypoint_index  +=  1 
325344                    # 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+                     )
327349                    _ , initial_crosstrack_y , _  =  self .rotation_yz  @ initial_error 
328350                    self .y_int  =  - initial_crosstrack_y  /  self .guidance_calculator .kappa 
329351                    waiting_at_waypoint  =  False 
330352                    wait_count  =  0 
331-                      
353+ 
332354                    # Reset filter with stop state 
333355                    # self.guidance_calculator.reset_filter_state(stop_state) 
334-                      
356+ 
335357                    # # Publish stop command and wait briefly 
336358                    # self.publish_guidance(stop_state) 
337359                    # time.sleep(2.0)  # Wait for 2 seconds to stabilize 
338-                     
339360
340361                    if  self .current_waypoint_index  >=  len (self .waypoints ) -  1 :
341362                        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+                         )
343366                        self .publish_guidance (final_commands )
344367                        result .success  =  True 
345368                        self .goal_handle .succeed ()
346369                        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+                 )
350379
351380                rotation_y  =  self .guidance_calculator .compute_rotation_y (self .pi_v )
352381                rotation_z  =  self .guidance_calculator .compute_rotation_z (self .pi_h )
@@ -366,6 +395,7 @@ def publish_guidance(self, commands: State):
366395        msg .yaw  =  commands .yaw 
367396        self .guidance_cmd_pub .publish (msg )
368397
398+ 
369399def  main (args = None ):
370400    """Main function to initialize and run the guidance node.""" 
371401    rclpy .init (args = args )
@@ -384,4 +414,4 @@ def main(args=None):
384414
385415
386416if  __name__  ==  '__main__' :
387-     main ()
417+     main ()
0 commit comments