Skip to content

Commit 6324465

Browse files
fixed merge confilts
2 parents 16acc18 + c11a072 commit 6324465

File tree

1 file changed

+78
-0
lines changed

1 file changed

+78
-0
lines changed

guidance/guidance_los/scripts/los_guidance_action_server.py

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,11 @@ def __init__(self):
4242
update_rate = self.get_parameter('update_rate').value
4343
self.update_period = 1.0 / update_rate
4444

45+
self.waiting_at_waypoint = False
46+
self.wait_cycles = int(1.0 / self.update_period)
47+
self.wait_count = 0
48+
self.y_int = 0.0
49+
4550
# Initialize filter status flag
4651
self.filter_initialized = False
4752

@@ -224,24 +229,53 @@ def calculate_guidance(self) -> State:
224229
self.state.as_pos_array()
225230
- self.waypoints[self.current_waypoint_index].as_pos_array()
226231
)
232+
error = self.guidance_calculator.state_as_pos_array(
233+
self.state - self.waypoints[self.current_waypoint_index]
234+
)
227235
_, crosstrack_y, crosstrack_z = self.rotation_yz @ error
236+
228237
alpha_c = self.guidance_calculator.calculate_alpha_c(
229238
self.u, self.v, self.w, self.phi
239+
self.state.twist.linear_x,
240+
self.state.twist.linear_y,
241+
self.state.twist.linear_z,
242+
self.state.pose.pitch,
230243
)
244+
231245
beta_c = self.guidance_calculator.calculate_beta_c(
232246
self.u, self.v, self.w, self.phi, self.pitch, alpha_c
247+
self.state.twist.linear_x,
248+
self.state.twist.linear_y,
249+
self.state.twist.linear_z,
250+
self.state.pose.roll,
251+
self.state.pose.pitch,
252+
alpha_c,
233253
)
254+
234255
psi_d = self.guidance_calculator.compute_psi_d(
235256
self.waypoints[self.current_waypoint_index],
236257
self.waypoints[self.current_waypoint_index + 1],
237258
crosstrack_y,
238259
beta_c,
260+
self.y_int,
239261
)
262+
263+
y_int_dot = self.guidance_calculator.calculate_y_int_dot(
264+
crosstrack_y, self.y_int
265+
)
266+
self.y_int += y_int_dot * self.update_period
267+
240268
theta_d = self.guidance_calculator.compute_theta_d(
241269
self.waypoints[self.current_waypoint_index],
242270
self.waypoints[self.current_waypoint_index + 1],
243271
crosstrack_z,
244272
alpha_c,
273+
alpha_c,
274+
)
275+
276+
yaw_error = ssa(psi_d - self.state.pose.yaw)
277+
desired_surge = self.guidance_calculator.compute_desired_speed(
278+
yaw_error, self.norm, crosstrack_y
245279
)
246280
unfiltered_commands = State(
247281
surge_vel=self.desired_vel, pitch=theta_d, yaw=psi_d
@@ -251,11 +285,22 @@ def calculate_guidance(self) -> State:
251285
)
252286
return unfiltered_commands
253287

288+
unfiltered_commands = State()
289+
unfiltered_commands.twist.linear_x = desired_surge
290+
unfiltered_commands.pose.pitch = theta_d
291+
unfiltered_commands.pose.yaw = psi_d
292+
293+
filtered_commands = self.guidance_calculator.apply_reference_filter(
294+
unfiltered_commands
295+
)
296+
return filtered_commands
297+
254298
def execute_callback(self, goal_handle: ServerGoalHandle):
255299
"""Execute waypoint navigation action."""
256300
# Initialize navigation goal with lock
257301
with self._goal_lock:
258302
self.goal_handle = goal_handle
303+
259304
self.current_waypoint_index = 0
260305
self.waypoints = [self.state]
261306
incoming_waypoints = goal_handle.request.waypoints
@@ -281,6 +326,13 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
281326
self.rotation_yz = rotation_y.T @ rotation_z.T
282327

283328
feedback = NavigateWaypoints.Feedback()
329+
# Initialize integral control
330+
initial_error = self.guidance_calculator.state_as_pos_array(
331+
self.state - self.waypoints[self.current_waypoint_index]
332+
)
333+
_, initial_crosstrack_y, _ = self.rotation_yz @ initial_error
334+
self.y_int = -initial_crosstrack_y / self.guidance_calculator.kappa
335+
284336
result = NavigateWaypoints.Result()
285337

286338
# Monitor navigation progress
@@ -310,6 +362,32 @@ def execute_callback(self, goal_handle: ServerGoalHandle):
310362
self.get_logger().info('Waypoint reached')
311363
self.current_waypoint_index += 1
312364

365+
if self.norm < 0.5:
366+
if not waiting_at_waypoint:
367+
self.get_logger().info('Waypoint reached')
368+
waiting_at_waypoint = True
369+
stop_state = State()
370+
stop_state.pose.pitch = self.state.pose.pitch
371+
stop_state.pose.yaw = self.state.pose.yaw
372+
self.guidance_calculator.reset_filter_state(stop_state)
373+
374+
if wait_count < wait_cycles:
375+
stop_command = State()
376+
stop_command.pose.pitch = self.state.pose.pitch
377+
stop_command.pose.yaw = self.state.pose.yaw
378+
self.publish_guidance(stop_command)
379+
wait_count += 1
380+
else:
381+
self.current_waypoint_index += 1
382+
# Reset integral term for new waypoint
383+
initial_error = self.guidance_calculator.state_as_pos_array(
384+
self.state - self.waypoints[self.current_waypoint_index]
385+
)
386+
_, initial_crosstrack_y, _ = self.rotation_yz @ initial_error
387+
self.y_int = -initial_crosstrack_y / self.guidance_calculator.kappa
388+
waiting_at_waypoint = False
389+
wait_count = 0
390+
313391
if self.current_waypoint_index >= len(self.waypoints) - 1:
314392
self.get_logger().info('All waypoints reached!')
315393
final_commands = State(

0 commit comments

Comments
 (0)