mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: use percent_input() for flaps
This commit is contained in:
parent
a788405c8b
commit
0d6064034a
@ -856,7 +856,7 @@ static void set_servos(void)
|
|||||||
RC_Channel *flapin = RC_Channel::rc_channel(g.flapin_channel-1);
|
RC_Channel *flapin = RC_Channel::rc_channel(g.flapin_channel-1);
|
||||||
if (flapin != NULL && !failsafe.ch3_failsafe && failsafe.ch3_counter == 0) {
|
if (flapin != NULL && !failsafe.ch3_failsafe && failsafe.ch3_counter == 0) {
|
||||||
flapin->input();
|
flapin->input();
|
||||||
manual_flap_percent = constrain_int16(flapin->norm_input() * 100, -100, 100);
|
manual_flap_percent = flapin->percent_input();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (auto_throttle_mode) {
|
if (auto_throttle_mode) {
|
||||||
|
Loading…
Reference in New Issue
Block a user