mirror of https://github.com/ArduPilot/ardupilot
Copter: make terrain failure strings human-readable
This commit is contained in:
parent
f65bee80dc
commit
7bbc699165
|
@ -236,37 +236,38 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
|||
#if MODE_RTL_ENABLED == ENABLED
|
||||
if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) {
|
||||
// get terrain source from wpnav
|
||||
const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s";
|
||||
switch (copter.wp_nav->get_terrain_source()) {
|
||||
case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "RTL_ALT_TYPE=1 but no terrain data");
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no terrain data");
|
||||
return false;
|
||||
break;
|
||||
case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
|
||||
if (!copter.rangefinder_state.enabled || !copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "RTL_ALT_TYPE=1 but no rangefinder");
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no rangefinder");
|
||||
return false;
|
||||
}
|
||||
// check if RTL_ALT is higher than rangefinder's max range
|
||||
if (copter.g.rtl_altitude > copter.rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "RTL_ALT_TYPE=1 but RTL_ALT>RNGFND_MAX_CM");
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "RTL_ALT>RNGFND_MAX_CM");
|
||||
return false;
|
||||
}
|
||||
break;
|
||||
case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
if (!copter.terrain.enabled()) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "RTL_ALT_TYPE=1 but terrain disabled");
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "terrain disabled");
|
||||
return false;
|
||||
}
|
||||
// check terrain data is loaded
|
||||
uint16_t terr_pending, terr_loaded;
|
||||
copter.terrain.get_statistics(terr_pending, terr_loaded);
|
||||
if (terr_pending != 0) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "RTL_ALT_TYPE=1, waiting for terrain data");
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "waiting for terrain data");
|
||||
return false;
|
||||
}
|
||||
#else
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "RTL_ALT_TYPE=1 but terrain disabled");
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "terrain disabled");
|
||||
return false;
|
||||
#endif
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue