From 07e53fad184d9dc94b2fbcc900cf6a73d8b670c1 Mon Sep 17 00:00:00 2001 From: Adam M Rivera Date: Mon, 16 Apr 2012 14:03:33 -0500 Subject: [PATCH] commands_logic.pde: Added write to constrained value to EEPROM. --- ArduCopter/commands_logic.pde | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 1ac9b2cb13..36ebe85c15 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -294,7 +294,12 @@ static void do_land() static void do_approach() { - uint16_t target_alt = (uint16_t)(constrain((float)g.rtl_approach_alt, 1, 10) * 100); + // Set a contrained value to EEPROM + g.rtl_approach_alt.set(constrain((float)g.rtl_approach_alt, 1.0, 10.0)); + + // Get the target_alt in cm + uint16_t target_alt = (uint16_t)(g.rtl_approach_alt * 100); + // Make sure we are not using this to land and that we are currently above the target approach alt if(g.rtl_approach_alt >= 1 && current_loc.alt > target_alt){ wp_control = LOITER_MODE;