From a89d8cf9fc7ed4e4a9ada4403f4369bac81c2631 Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Fri, 5 Feb 2021 23:55:48 -0500 Subject: [PATCH] Copter: remove setting of rotor rpm in heli.cpp --- ArduCopter/heli.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index 2ea4e56a25..350bcbcbbb 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -159,11 +159,6 @@ void Copter::heli_update_rotor_speed_targets() // get rotor control method uint8_t rsc_control_mode = motors->get_rsc_mode(); - -#if RPM_ENABLED == ENABLED - // set rpm from rotor speed sensor - motors->set_rpm(rpm_sensor.get_rpm(0)); -#endif switch (rsc_control_mode) { case ROTOR_CONTROL_MODE_PASSTHROUGH: