mirror of https://github.com/ArduPilot/ardupilot
AP_Terrain: split sending terrain report from terrain request
This commit is contained in:
parent
11014cae06
commit
a401c98c74
|
@ -109,6 +109,9 @@ public:
|
|||
void send_request(mavlink_channel_t chan);
|
||||
|
||||
// handle terrain data and reports from GCS
|
||||
// send a terrain report for the current location, extrapolating height as we do for navigation:
|
||||
void send_report(mavlink_channel_t chan);
|
||||
// send a terrain report or Location loc
|
||||
void send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate);
|
||||
void handle_data(mavlink_channel_t chan, const mavlink_message_t &msg);
|
||||
void handle_terrain_check(mavlink_channel_t chan, const mavlink_message_t &msg);
|
||||
|
|
|
@ -115,17 +115,12 @@ void AP_Terrain::send_request(mavlink_channel_t chan)
|
|||
|
||||
Location loc;
|
||||
if (!AP::ahrs().get_location(loc)) {
|
||||
// we don't know where we are. Send a report and request any cached blocks.
|
||||
// we don't know where we are. Request any cached blocks.
|
||||
// this allows for download of mission items when we have no GPS lock
|
||||
loc = {};
|
||||
send_terrain_report(chan, loc, true);
|
||||
send_cache_request(chan);
|
||||
return;
|
||||
}
|
||||
|
||||
// always send a terrain report
|
||||
send_terrain_report(chan, loc, true);
|
||||
|
||||
// did we request recently?
|
||||
if (AP_HAL::millis() - last_request_time_ms[chan] < 2000) {
|
||||
// too soon to request again
|
||||
|
@ -207,6 +202,18 @@ void AP_Terrain::handle_data(mavlink_channel_t chan, const mavlink_message_t &ms
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
send a TERRAIN_REPORT for the current location
|
||||
*/
|
||||
void AP_Terrain::send_report(mavlink_channel_t chan)
|
||||
{
|
||||
Location loc;
|
||||
if (!AP::ahrs().get_location(loc)) {
|
||||
loc = {};
|
||||
}
|
||||
|
||||
send_terrain_report(chan, loc, true);
|
||||
}
|
||||
|
||||
/*
|
||||
send a TERRAIN_REPORT for a location
|
||||
|
|
Loading…
Reference in New Issue