mirror of https://github.com/ArduPilot/ardupilot
Plane: added arming check for terrain data
This commit is contained in:
parent
bad0120d3c
commit
2e32c753b9
|
@ -78,6 +78,21 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
|
|||
ret &= quadplane_checks(display_failure);
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
if (plane.g.terrain_follow || plane.mission.contains_terrain_relative()) {
|
||||
// check terrain data is loaded and healthy
|
||||
uint16_t terr_pending=0, terr_loaded=0;
|
||||
plane.terrain.get_statistics(terr_pending, terr_loaded);
|
||||
if (plane.terrain.status() != AP_Terrain::TerrainStatusOK) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "terrain data unhealthy");
|
||||
ret = false;
|
||||
} else if (terr_pending != 0) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "waiting for terrain data");
|
||||
ret = false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (plane.control_mode == &plane.mode_auto && plane.mission.num_commands() <= 1) {
|
||||
check_failed(display_failure, "No mission loaded");
|
||||
ret = false;
|
||||
|
|
Loading…
Reference in New Issue