mirror of https://github.com/ArduPilot/ardupilot
Copter: auto takeoff may trigger terrain failsafe
This commit is contained in:
parent
6245b3aa16
commit
658298ed1d
|
@ -112,7 +112,8 @@ void Mode::auto_takeoff_run()
|
||||||
// get terrain offset
|
// get terrain offset
|
||||||
float terr_offset = 0.0f;
|
float terr_offset = 0.0f;
|
||||||
if (auto_takeoff_terrain_alt && !wp_nav->get_terrain_offset(terr_offset)) {
|
if (auto_takeoff_terrain_alt && !wp_nav->get_terrain_offset(terr_offset)) {
|
||||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "auto takeoff: failed to get terrain offset");
|
// trigger terrain failsafe
|
||||||
|
copter.failsafe_terrain_on_event();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue