From 5ce731fa0069210bb57bcf09f49f7785f918c7e8 Mon Sep 17 00:00:00 2001 From: muramura Date: Thu, 31 Aug 2023 07:14:34 +0900 Subject: [PATCH] Copter: Two processes in one --- ArduCopter/mode_systemid.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 1a942780b8..50fe12749d 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -261,11 +261,7 @@ void ModeSystemId::run() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); // output pilot's throttle - if (copter.is_tradheli()) { - attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); - } else { - attitude_control->set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt); - } + attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt); if (log_subsample <= 0) { log_data();