11from  dataclasses  import  dataclass , field 
22
33import  numpy  as  np 
4- from  vortex_utils .python_utils  import  State , ssa 
4+ 
5+ 
6+ @dataclass  
7+ class  State :
8+     x : float  =  0.0 
9+     y : float  =  0.0 
10+     z : float  =  0.0 
11+     pitch : float  =  0.0 
12+     yaw : float  =  0.0 
13+     surge_vel : float  =  0.0 
14+ 
15+     def  __add__ (self , other : "State" ) ->  "State" :
16+         return  State (
17+             x = self .x  +  other .x ,
18+             y = self .y  +  other .y ,
19+             z = self .z  +  other .z ,
20+             pitch = self .pitch  +  other .pitch ,
21+             yaw = self .yaw  +  other .yaw ,
22+         )
23+ 
24+     def  __sub__ (self , other : "State" ) ->  "State" :
25+         return  State (
26+             x = self .x  -  other .x ,
27+             y = self .y  -  other .y ,
28+             z = self .z  -  other .z ,
29+             pitch = self .pitch  -  other .pitch ,
30+             yaw = self .yaw  -  other .yaw ,
31+         )
32+ 
33+     def  as_los_array (self ):
34+         return  np .array ([self .surge_vel , self .pitch , self .yaw ])
35+     
36+     def  as_pos_array (self ):
37+         return  np .array ([self .x , self .y , self .z ])
538
639
740@dataclass (slots = True ) 
@@ -56,6 +89,44 @@ def __init__(self, los_params: LOSParameters, filter_params: FilterParameters):
5689        self .setup_filter_matrices ()
5790        self .lookahead_h  =  2.0 
5891        self .lookahead_v  =  2.0 
92+         self .kappa  =  0.001 
93+ 
94+     @staticmethod  
95+     def  quaternion_to_euler_angle (w : float , x : float , y : float , z : float ) ->  tuple :
96+         """Function to convert quaternion to euler angles. 
97+ 
98+         Parameters: 
99+             w: float: w component of quaternion 
100+             x: float: x component of quaternion 
101+             y: float: y component of quaternion 
102+             z: float: z component of quaternion 
103+ 
104+         Returns: 
105+             phi: float: roll angle 
106+             theta: float: pitch angle 
107+             psi: float: yaw angle 
108+ 
109+         """ 
110+         y_square  =  y  *  y 
111+ 
112+         t0  =  + 2.0  *  (w  *  x  +  y  *  z )
113+         t1  =  + 1.0  -  2.0  *  (x  *  x  +  y_square )
114+         phi  =  np .arctan2 (t0 , t1 )
115+ 
116+         t2  =  + 2.0  *  (w  *  y  -  z  *  x )
117+         t2  =  + 1.0  if  t2  >  + 1.0  else  t2 
118+         t2  =  - 1.0  if  t2  <  - 1.0  else  t2 
119+         theta  =  np .arcsin (t2 )
120+ 
121+         t3  =  + 2.0  *  (w  *  z  +  x  *  y )
122+         t4  =  + 1.0  -  2.0  *  (y_square  +  z  *  z )
123+         psi  =  np .arctan2 (t3 , t4 )
124+ 
125+         return  phi , theta , psi 
126+ 
127+     @staticmethod  
128+     def  ssa (angle : float ) ->  float :
129+         return  (angle  +  np .pi ) %  (2  *  np .pi ) -  np .pi 
59130
60131    def  setup_filter_matrices (self ):
61132        omega  =  np .diag (self .filter_params .omega_diag )
@@ -75,23 +146,21 @@ def setup_filter_matrices(self):
75146        self .Bd [6 :9 , :] =  omega_cubed 
76147
77148    def  compute_raw_los_guidance (self , current_pos : State , target_pos : State ) ->  State :
78-         dx  =  target_pos .pose . x  -  current_pos . pose .x 
79-         dy  =  target_pos .pose . y  -  current_pos . pose .y 
149+         dx  =  target_pos .x  -  current_pos .x 
150+         dy  =  target_pos .y  -  current_pos .y 
80151
81152        self .horizontal_distance  =  np .sqrt (dx ** 2  +  dy ** 2 )
82153        desired_yaw  =  np .arctan2 (dy , dx )
83-         yaw_error  =  ssa (desired_yaw  -  current_pos . pose .yaw )
154+         yaw_error  =  self . ssa (desired_yaw  -  current_pos .yaw )
84155
85-         depth_error  =  target_pos .pose . z  -  current_pos . pose .z 
156+         depth_error  =  target_pos .z  -  current_pos .z 
86157        desired_pitch  =  self .compute_pitch_command (
87158            depth_error , self .horizontal_distance 
88159        )
89160
90161        desired_surge  =  self .compute_desired_speed (yaw_error , self .horizontal_distance )
91-         commands  =  State ()
92-         commands .twist .linear_x  =  desired_surge 
93-         commands .pose .pitch  =  desired_pitch 
94-         commands .pose .yaw  =  desired_yaw 
162+ 
163+         commands  =  State (surge_vel = desired_surge , pitch = desired_pitch , yaw = desired_yaw )
95164
96165        return  commands 
97166
@@ -110,125 +179,88 @@ def compute_pitch_command(
110179            self .los_params .max_pitch_angle ,
111180        )
112181
113-     def  compute_desired_speed (
114-         self , yaw_error : float , distance_to_target : float 
115-     ) ->  float :
116-         """Compute speed command with yaw and distance-based scaling.""" 
182+     def  compute_desired_speed (self , yaw_error : float , distance_to_target : float , crosstrack_y : float ) ->  float :
183+         """ 
184+         Compute speed command with yaw error, distance and crosstrack-based scaling. 
185+          
186+         Args: 
187+             yaw_error: Error in yaw angle (radians) 
188+             distance_to_target: Distance to target (meters) 
189+             crosstrack_y: Cross-track error in y direction (meters) 
190+         """ 
117191        yaw_factor  =  np .cos (yaw_error )
118-         distance_factor  =  min (
119-             1.0 , distance_to_target  /  self .los_params .lookahead_distance_max 
120-         )
121-         desired_speed  =  self .los_params .nominal_speed  *  yaw_factor  *  distance_factor 
192+         distance_factor  =  min (1.0 , distance_to_target  /  self .los_params .lookahead_distance_max )
193+         crosstrack_factor  =  1.0  /  (1.0  +  abs (crosstrack_y ))
194+         desired_speed  =  self .los_params .nominal_speed  *  yaw_factor  *  distance_factor  *  crosstrack_factor 
122195        return  max (self .los_params .min_speed , desired_speed )
123196
124197    def  apply_reference_filter (self , commands : State ) ->  State :
125-         los_array  =  self .state_to_los_array (commands )
126-         x_dot  =  self .Ad  @ self .x  +  self .Bd  @ los_array 
198+         x_dot  =  self .Ad  @ self .x  +  self .Bd  @ commands .as_los_array ()
127199        self .x  =  self .x  +  x_dot  *  self .los_params .dt 
128- 
129-         commands .twist .linear_x  =  self .x [0 ]
130-         commands .pose .pitch  =  self .x [1 ]
131-         commands .pose .yaw  =  self .x [2 ]
132- 
133-         return  commands 
200+         return  State (surge_vel = self .x [0 ], pitch = self .x [1 ], yaw = self .x [2 ])
134201
135202    def  compute_guidance (self , current_pos : State , target_pos : State ) ->  State :
136203        raw_commands  =  self .compute_raw_los_guidance (current_pos , target_pos )
137204
138205        filtered_commands  =  self .apply_reference_filter (raw_commands )
139-         filtered_commands .pose . pitch  =  ssa (filtered_commands . pose .pitch )
140-         filtered_commands .pose . yaw  =  ssa (filtered_commands . pose .yaw )
206+         filtered_commands .pitch  =  self . ssa (filtered_commands .pitch )
207+         filtered_commands .yaw  =  self . ssa (filtered_commands .yaw )
141208        return  filtered_commands 
142209
143210    def  reset_filter_state (self , current_state : State ) ->  None :
144211        self .x  =  np .zeros (9 )
145-         current_state_array  =  self . state_to_los_array (current_state )
212+         current_state_array  =  np . array (current_state . as_los_array (),  copy = True )
146213        self .x [0 :3 ] =  current_state_array 
147214
148-     @staticmethod  
149-     def  state_to_los_array (state : State ) ->  np .ndarray :
150-         """Converts State object to array with surge velocity, pitch, and yaw.""" 
151-         return  np .array ([state .twist .linear_x , state .pose .pitch , state .pose .yaw ])
152- 
153-     @staticmethod  
154-     def  state_as_pos_array (state : State ) ->  np .ndarray :
155-         """Converts State object to array with x, y, z.""" 
156-         return  np .array ([state .pose .x , state .pose .y , state .pose .z ])
157- 
158215    @staticmethod  
159216    def  compute_pi_h (current_waypoint : State , next_waypoint : State ) ->  float :
160-         dx  =  next_waypoint .pose . x  -  current_waypoint . pose .x 
161-         dy  =  next_waypoint .pose . y  -  current_waypoint . pose .y 
217+         dx  =  next_waypoint .x  -  current_waypoint .x 
218+         dy  =  next_waypoint .y  -  current_waypoint .y 
162219        return  np .arctan2 (dy , dx )
163- 
220+      
164221    @staticmethod  
165222    def  compute_pi_v (current_waypoint : State , next_waypoint : State ) ->  float :
166-         dz  =  next_waypoint .pose .z  -  current_waypoint .pose .z 
167-         horizontal_distance  =  np .sqrt (
168-             (next_waypoint .pose .x  -  current_waypoint .pose .x ) **  2 
169-             +  (next_waypoint .pose .y  -  current_waypoint .pose .y ) **  2 
170-         )
223+         dz  =  next_waypoint .z  -  current_waypoint .z 
224+         horizontal_distance  =  np .sqrt ((next_waypoint .x  -  current_waypoint .x )** 2  +  (next_waypoint .y  -  current_waypoint .y )** 2 )
171225        return  np .arctan2 (- dz , horizontal_distance )
172- 
226+      
173227    @staticmethod  
174228    def  compute_rotation_y (pi_v : float ) ->  np .ndarray :
175-         return  np .array (
176-             [
177-                 [np .cos (pi_v ), 0 , np .sin (pi_v )],
178-                 [0 , 1 , 0 ],
179-                 [- np .sin (pi_v ), 0 , np .cos (pi_v )],
180-             ]
181-         )
182- 
229+         return  np .array ([
230+             [np .cos (pi_v ), 0 , np .sin (pi_v )],
231+             [0 , 1 , 0 ],
232+             [- np .sin (pi_v ), 0 , np .cos (pi_v )]
233+         ])
234+     
183235    @staticmethod  
184236    def  compute_rotation_z (pi_h : float ) ->  np .ndarray :
185-         return  np .array (
186-             [
187-                 [np .cos (pi_h ), - np .sin (pi_h ), 0 ],
188-                 [np .sin (pi_h ), np .cos (pi_h ), 0 ],
189-                 [0 , 0 , 1 ],
190-             ]
191-         )
192- 
193-     def  compute_psi_d (
194-         self ,
195-         current_waypoint : State ,
196-         next_waypoint : State ,
197-         crosstrack_y : float ,
198-         beta_c : float ,
199-     ) ->  float :
237+         return  np .array ([
238+             [np .cos (pi_h ), - np .sin (pi_h ), 0 ],
239+             [np .sin (pi_h ), np .cos (pi_h ), 0 ],
240+             [0 , 0 , 1 ]
241+         ])
242+     
243+     def  compute_psi_d (self , current_waypoint : State , next_waypoint : State , crosstrack_y : float , y_int : float ) ->  float :
200244        pi_h  =  self .compute_pi_h (current_waypoint , next_waypoint )
201-         psi_d  =  pi_h  -  np .arctan (crosstrack_y  /  self .lookahead_h )  -   beta_c 
202-         psi_d  =  ssa (psi_d )
245+         psi_d  =  pi_h  -  np .arctan (( crosstrack_y  +  self .kappa )  /   self . lookahead_h ) 
246+         psi_d  =  self . ssa (psi_d )
203247        return  psi_d 
204- 
205-     def  compute_theta_d (
206-         self ,
207-         current_waypoint : State ,
208-         next_waypoint : State ,
209-         crosstrack_z : float ,
210-         alpha_c : float ,
211-     ) ->  float :
248+     
249+     def  compute_theta_d (self , current_waypoint : State , next_waypoint : State , crosstrack_z : float , alpha_c : float ) ->  float :
212250        pi_v  =  self .compute_pi_v (current_waypoint , next_waypoint )
213251        theta_d  =  pi_v  +  np .arctan (crosstrack_z  /  self .lookahead_v ) +  alpha_c 
214-         theta_d  =  ssa (theta_d )
252+         theta_d  =  self . ssa (theta_d )
215253        return  theta_d 
216254
217255    @staticmethod  
218256    def  calculate_alpha_c (u : float , v : float , w : float , phi : float ) ->  float :
219-         if  u  ==  0 :
220-             return  0 
221-         return  np .arctan (
222-             (v  *  np .sin (phi ) +  w  *  np .cos (phi )) /  u 
223-         )  # Slide 104 in Fossen 2024 
224- 
257+         return  np .arctan ((v  *  np .sin (phi ) +  w  *  np .cos (phi )) /  u ) # Slide 104 in Fossen 2024 
258+     
225259    @staticmethod  
226-     def  calculate_beta_c (
227-         u : float , v : float , w : float , phi : float , theta : float , alpha_c : float 
228-     ) ->  float :
229-         u_v  =  u  *  np .sqrt (1  +  np .tan (alpha_c ) **  2 )
230-         if  u_v  ==  0 :
231-             return  0 
232-         return  np .arctan (
233-             (v  *  np .cos (phi ) -  w  *  np .sin (phi )) /  (u_v  *  np .cos (theta  -  alpha_c ))
234-         )  # Slide 104 in Fossen 2024 
260+     def  calculate_beta_c (u : float , v : float , w : float , phi : float , theta : float , alpha_c : float ) ->  float :
261+         U_v  =  u  *  np .sqrt (1  +  np .tan (alpha_c )** 2 )
262+         return  np .arctan ((v  *  np .cos (phi ) -  w  *  np .sin (phi )) /  (U_v  *  np .cos (theta  -  alpha_c ))) # Slide 104 in Fossen 2024 
263+ 
264+     def  calculate_y_int_dot (self , crosstrack_y , y_int ):
265+         y_int_dot  =  (self .lookahead_h  *  crosstrack_y ) /  (self .lookahead_h ** 2  +  (crosstrack_y  +  self .kappa  *  y_int )** 2 )
266+         return  y_int_dot 
0 commit comments