mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
throttle Cruise error fixed
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1279 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
01ee447555
commit
e5bb2b419b
@ -179,7 +179,7 @@ void save_EEPROM_throttle_cruise(void)
|
||||
|
||||
void read_EEPROM_throttle_cruise(void)
|
||||
{
|
||||
throttle_cruise = eeprom_read_word((uint16_t *) EE_FRAME);
|
||||
throttle_cruise = eeprom_read_word((uint16_t *) EE_THROTTLE_CRUISE);
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
@ -277,7 +277,7 @@ void save_EEPROM_radio(void)
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
|
||||
// configs are the basics
|
||||
void read_EEPROM_configs(void)
|
||||
{
|
||||
throttle_min = eeprom_read_word((uint16_t *) EE_THROTTLE_MIN);
|
||||
|
Loading…
Reference in New Issue
Block a user