From d9dedf3fe8bca8de5e614875885ace9d555d88e2 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 14 Dec 2022 08:54:12 +0000 Subject: [PATCH] Copter: autoyaw: weathervane: include roll trim for helis --- ArduCopter/autoyaw.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/autoyaw.cpp b/ArduCopter/autoyaw.cpp index 4cd9d4c0c7..6853789ee3 100644 --- a/ArduCopter/autoyaw.cpp +++ b/ArduCopter/autoyaw.cpp @@ -350,7 +350,7 @@ void Mode::AutoYaw::update_weathervane(const int16_t pilot_yaw_cds) float yaw_rate_cds; if (copter.g2.weathervane.get_yaw_out(yaw_rate_cds, pilot_yaw_cds, copter.flightmode->get_alt_above_ground_cm()*0.01, - copter.pos_control->get_roll_cd(), + copter.pos_control->get_roll_cd()-copter.attitude_control->get_roll_trim_cd(), copter.pos_control->get_pitch_cd(), copter.flightmode->is_taking_off(), copter.flightmode->is_landing())) {