mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
Copter: fixed heli rotor speed control from AP_Motors refactor
This commit is contained in:
parent
79ffc28f68
commit
55ad1548e4
@ -143,7 +143,7 @@ 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();
|
||||||
|
|
||||||
float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)g.rc_8.get_control_in()/1000.0f);
|
float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)g.rc_8.get_control_in()) * 0.001f;
|
||||||
|
|
||||||
switch (rsc_control_mode) {
|
switch (rsc_control_mode) {
|
||||||
case ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH:
|
case ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH:
|
||||||
|
Loading…
Reference in New Issue
Block a user