throttle Cruise error fixed

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1279 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2010-12-26 20:04:57 +00:00
parent d4c3574a88
commit 94f2d4e66e
1 changed files with 2 additions and 2 deletions

View File

@ -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);