mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
Copter: Guided add terrain failsafe
This commit is contained in:
parent
9ce91211e2
commit
7defb6d3e6
@ -552,8 +552,8 @@ void ModeGuided::pos_control_run()
|
||||
// calculate terrain adjustments
|
||||
float terr_offset = 0.0f;
|
||||
if (guided_pos_terrain_alt && !wp_nav->get_terrain_offset(terr_offset)) {
|
||||
// if we don't have terrain altitude then stop
|
||||
init(true);
|
||||
// failure to set destination can only be because of missing terrain data
|
||||
copter.failsafe_terrain_on_event();
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user