mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
commands_logic.pde: Added write to constrained value to EEPROM.
This commit is contained in:
parent
3135cd91d0
commit
3146c22ea8
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user