From 9cf63a5407a608b0213449e8c40c394695100d25 Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Sat, 14 Sep 2024 20:14:44 -0700 Subject: [PATCH] Sub: fully init yaw control on guided submode start --- ArduSub/mode_guided.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduSub/mode_guided.cpp b/ArduSub/mode_guided.cpp index ff1bb07df5..6002a2c94f 100644 --- a/ArduSub/mode_guided.cpp +++ b/ArduSub/mode_guided.cpp @@ -93,6 +93,7 @@ void ModeGuided::guided_pos_control_start() sub.wp_nav.set_wp_destination(stopping_point, false); // initialise yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(get_default_auto_yaw_mode(false)); } @@ -111,6 +112,7 @@ void ModeGuided::guided_vel_control_start() position_control->init_xy_controller(); // pilot always controls yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(AUTO_YAW_HOLD); } @@ -129,6 +131,7 @@ void ModeGuided::guided_posvel_control_start() position_control->init_xy_controller(); // pilot always controls yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(AUTO_YAW_HOLD); } @@ -153,6 +156,7 @@ void ModeGuided::guided_angle_control_start() guided_angle_state.climb_rate_cms = 0.0f; // pilot always controls yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(AUTO_YAW_HOLD); }