mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
added set_new_altitude call()
This commit is contained in:
parent
0c9dc11ac1
commit
78925d57c2
@ -14,7 +14,8 @@ static void failsafe_on_event()
|
|||||||
// do_rtl sets the altitude to the current altitude by default
|
// do_rtl sets the altitude to the current altitude by default
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
// We add an additional 10m to the current altitude
|
// We add an additional 10m to the current altitude
|
||||||
next_WP.alt += 1000;
|
//next_WP.alt += 1000;
|
||||||
|
set_new_altitude(target_altitude + 1000);
|
||||||
}
|
}
|
||||||
// 2 = Stay in AUTO and ignore failsafe
|
// 2 = Stay in AUTO and ignore failsafe
|
||||||
|
|
||||||
@ -24,7 +25,8 @@ static void failsafe_on_event()
|
|||||||
// do_rtl sets the altitude to the current altitude by default
|
// do_rtl sets the altitude to the current altitude by default
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
// We add an additional 10m to the current altitude
|
// We add an additional 10m to the current altitude
|
||||||
next_WP.alt += 1000;
|
//next_WP.alt += 1000;
|
||||||
|
set_new_altitude(target_altitude + 1000);
|
||||||
}else{
|
}else{
|
||||||
// We have no GPS so we must land
|
// We have no GPS so we must land
|
||||||
set_mode(LAND);
|
set_mode(LAND);
|
||||||
|
Loading…
Reference in New Issue
Block a user