From 94f2d4e66e37f8146c191b9a36b65ac72a78a78d Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sun, 26 Dec 2010 20:04:57 +0000 Subject: [PATCH] throttle Cruise error fixed git-svn-id: https://arducopter.googlecode.com/svn/trunk@1279 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/EEPROM.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopterMega/EEPROM.pde b/ArduCopterMega/EEPROM.pde index 7e51b9f13c..4a8cf4b6f4 100644 --- a/ArduCopterMega/EEPROM.pde +++ b/ArduCopterMega/EEPROM.pde @@ -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);