mirror of https://github.com/ArduPilot/ardupilot
AP_Terrain: move terrain prearm checks to AP_Terrain
This commit is contained in:
parent
96ef34acac
commit
d688e6068b
|
@ -364,6 +364,19 @@ void AP_Terrain::update(void)
|
|||
|
||||
}
|
||||
|
||||
bool AP_Terrain::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) const
|
||||
{
|
||||
// check no outstanding requests for data:
|
||||
uint16_t terr_pending, terr_loaded;
|
||||
get_statistics(terr_pending, terr_loaded);
|
||||
if (terr_pending != 0) {
|
||||
hal.util->snprintf(failure_msg, failure_msg_len, "waiting for terrain data");
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void AP_Terrain::log_terrain_data()
|
||||
{
|
||||
if (!allocate()) {
|
||||
|
|
|
@ -107,6 +107,8 @@ public:
|
|||
// return status enum for health reporting
|
||||
enum TerrainStatus status(void) const { return system_status; }
|
||||
|
||||
bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) const;
|
||||
|
||||
// send any pending terrain request message
|
||||
bool send_cache_request(mavlink_channel_t chan);
|
||||
void send_request(mavlink_channel_t chan);
|
||||
|
|
Loading…
Reference in New Issue