mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Terrain: fixed build for periph
needed for SITL periph rangefinder
This commit is contained in:
parent
791d0acefe
commit
9706a207b1
@ -487,7 +487,7 @@ bool AP_Terrain::allocate(void)
|
||||
}
|
||||
cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0]));
|
||||
if (cache == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed");
|
||||
memory_alloc_failed = true;
|
||||
return false;
|
||||
}
|
||||
|
@ -37,6 +37,9 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcache)
|
||||
{
|
||||
#if !HAL_GCS_ENABLED
|
||||
return false;
|
||||
#else
|
||||
struct grid_block &grid = gcache.grid;
|
||||
|
||||
if (options.get() & uint16_t(Options::DisableDownload)) {
|
||||
@ -72,6 +75,7 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcac
|
||||
last_request_time_ms[chan] = AP_HAL::millis();
|
||||
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
@ -211,6 +215,7 @@ void AP_Terrain::handle_data(mavlink_channel_t chan, const mavlink_message_t &ms
|
||||
*/
|
||||
void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate)
|
||||
{
|
||||
#if HAL_GCS_ENABLED
|
||||
float terrain_height = 0;
|
||||
uint16_t spacing = 0;
|
||||
if (height_amsl(loc, terrain_height)) {
|
||||
@ -232,6 +237,7 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc
|
||||
terrain_height, current_height,
|
||||
pending, loaded);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user