mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
fixed dead zone load/save
This commit is contained in:
parent
150a67c262
commit
37cabb4cfa
@ -176,6 +176,7 @@ RC_Channel::load_eeprom(void)
|
||||
radio_trim.load();
|
||||
radio_max.load();
|
||||
_reverse.load();
|
||||
_dead_zone.load();
|
||||
}
|
||||
|
||||
void
|
||||
@ -185,6 +186,7 @@ RC_Channel::save_eeprom(void)
|
||||
radio_trim.save();
|
||||
radio_max.save();
|
||||
_reverse.save();
|
||||
_dead_zone.save();
|
||||
}
|
||||
|
||||
// ------------------------------------------
|
||||
|
Loading…
Reference in New Issue
Block a user