mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: remove setting of rotor rpm in heli.cpp
This commit is contained in:
parent
05e8285f93
commit
a89d8cf9fc
@ -160,11 +160,6 @@ void Copter::heli_update_rotor_speed_targets()
|
|||||||
// get rotor control method
|
// get rotor control method
|
||||||
uint8_t rsc_control_mode = motors->get_rsc_mode();
|
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) {
|
switch (rsc_control_mode) {
|
||||||
case ROTOR_CONTROL_MODE_PASSTHROUGH:
|
case ROTOR_CONTROL_MODE_PASSTHROUGH:
|
||||||
// pass through pilot desired rotor speed from the RC
|
// pass through pilot desired rotor speed from the RC
|
||||||
|
Loading…
Reference in New Issue
Block a user