mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
commands_logic: Added do_approach() to set the new target alt based on the user defined value.
This commit is contained in:
parent
83fe6733d4
commit
cfe3b58248
@ -292,6 +292,27 @@ static void do_land()
|
||||
set_new_altitude(-1000);
|
||||
}
|
||||
|
||||
static void do_approach()
|
||||
{
|
||||
wp_control = LOITER_MODE;
|
||||
|
||||
// just to make sure
|
||||
land_complete = false;
|
||||
|
||||
// landing boost lowers the main throttle to mimmick
|
||||
// the effect of a user's hand
|
||||
landing_boost = 0;
|
||||
|
||||
// A counter that goes up if our climb rate stalls out.
|
||||
ground_detector = 0;
|
||||
|
||||
// hold at our current location
|
||||
set_next_WP(¤t_loc);
|
||||
|
||||
// Set target alt based on user setting
|
||||
set_new_altitude(g.rtl_approach_alt * 100);
|
||||
}
|
||||
|
||||
static void do_loiter_unlimited()
|
||||
{
|
||||
wp_control = LOITER_MODE;
|
||||
|
Loading…
Reference in New Issue
Block a user