mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 10:23:59 -04:00
AP_Terrain: make terrain request times per channel
otherwise we can miss sending one if we send first to a channel not being listened to
This commit is contained in:
parent
3a9d7363ea
commit
c7044c4f91
@ -58,7 +58,6 @@ AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rall
|
|||||||
mission(_mission),
|
mission(_mission),
|
||||||
rally(_rally),
|
rally(_rally),
|
||||||
disk_io_state(DiskIoIdle),
|
disk_io_state(DiskIoIdle),
|
||||||
last_request_time_ms(0),
|
|
||||||
fd(-1),
|
fd(-1),
|
||||||
timer_setup(false),
|
timer_setup(false),
|
||||||
file_lat_degrees(0),
|
file_lat_degrees(0),
|
||||||
@ -72,6 +71,7 @@ AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rall
|
|||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
memset(&home_loc, 0, sizeof(home_loc));
|
memset(&home_loc, 0, sizeof(home_loc));
|
||||||
memset(&disk_block, 0, sizeof(disk_block));
|
memset(&disk_block, 0, sizeof(disk_block));
|
||||||
|
memset(last_request_time_ms, 0, sizeof(last_request_time_ms));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -352,7 +352,7 @@ private:
|
|||||||
union grid_io_block disk_block;
|
union grid_io_block disk_block;
|
||||||
|
|
||||||
// last time we asked for more grids
|
// last time we asked for more grids
|
||||||
uint32_t last_request_time_ms;
|
uint32_t last_request_time_ms[MAVLINK_COMM_NUM_BUFFERS];
|
||||||
|
|
||||||
static const uint64_t bitmap_mask = (((uint64_t)1U)<<(TERRAIN_GRID_BLOCK_MUL_X*TERRAIN_GRID_BLOCK_MUL_Y)) - 1;
|
static const uint64_t bitmap_mask = (((uint64_t)1U)<<(TERRAIN_GRID_BLOCK_MUL_X*TERRAIN_GRID_BLOCK_MUL_Y)) - 1;
|
||||||
|
|
||||||
|
@ -64,7 +64,7 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcac
|
|||||||
ask the GCS to send a set of 4x4 grids
|
ask the GCS to send a set of 4x4 grids
|
||||||
*/
|
*/
|
||||||
mavlink_msg_terrain_request_send(chan, grid.lat, grid.lon, grid_spacing, bitmap_mask & ~grid.bitmap);
|
mavlink_msg_terrain_request_send(chan, grid.lat, grid.lon, grid_spacing, bitmap_mask & ~grid.bitmap);
|
||||||
last_request_time_ms = hal.scheduler->millis();
|
last_request_time_ms[chan] = hal.scheduler->millis();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -102,7 +102,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan)
|
|||||||
send_terrain_report(chan, loc, true);
|
send_terrain_report(chan, loc, true);
|
||||||
|
|
||||||
// did we request recently?
|
// did we request recently?
|
||||||
if (hal.scheduler->millis() - last_request_time_ms < 2000) {
|
if (hal.scheduler->millis() - last_request_time_ms[chan] < 2000) {
|
||||||
// too soon to request again
|
// too soon to request again
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user