Browse Source

AP_Terrain: use millis/micros/panic functions

master
Caio Marcelo de Oliveira Filho 9 years ago committed by Randy Mackay
parent
commit
0aa520a273
  1. 2
      libraries/AP_Terrain/AP_Terrain.cpp
  2. 4
      libraries/AP_Terrain/TerrainGCS.cpp
  3. 2
      libraries/AP_Terrain/TerrainIO.cpp
  4. 4
      libraries/AP_Terrain/TerrainUtil.cpp

2
libraries/AP_Terrain/AP_Terrain.cpp

@ -357,7 +357,7 @@ void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash) @@ -357,7 +357,7 @@ void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash)
struct log_TERRAIN pkt = {
LOG_PACKET_HEADER_INIT(LOG_TERRAIN_MSG),
time_us : hal.scheduler->micros64(),
time_us : AP_HAL::micros64(),
status : (uint8_t)status(),
lat : loc.lat,
lng : loc.lng,

4
libraries/AP_Terrain/TerrainGCS.cpp

@ -64,7 +64,7 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcac @@ -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
*/
mavlink_msg_terrain_request_send(chan, grid.lat, grid.lon, grid_spacing, bitmap_mask & ~grid.bitmap);
last_request_time_ms[chan] = hal.scheduler->millis();
last_request_time_ms[chan] = AP_HAL::millis();
return true;
}
@ -102,7 +102,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan) @@ -102,7 +102,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan)
send_terrain_report(chan, loc, true);
// did we request recently?
if (hal.scheduler->millis() - last_request_time_ms[chan] < 2000) {
if (AP_HAL::millis() - last_request_time_ms[chan] < 2000) {
// too soon to request again
return;
}

2
libraries/AP_Terrain/TerrainIO.cpp

@ -97,7 +97,7 @@ void AP_Terrain::schedule_disk_io(void) @@ -97,7 +97,7 @@ void AP_Terrain::schedule_disk_io(void)
cache[cache_idx].grid = disk_block.block;
}
cache[cache_idx].state = GRID_CACHE_VALID;
cache[cache_idx].last_access_ms = hal.scheduler->millis();
cache[cache_idx].last_access_ms = AP_HAL::millis();
}
disk_io_state = DiskIoIdle;
break;

4
libraries/AP_Terrain/TerrainUtil.cpp

@ -124,7 +124,7 @@ AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(const struct grid_info &info @@ -124,7 +124,7 @@ AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(const struct grid_info &info
if (cache[i].grid.lat == info.grid_lat &&
cache[i].grid.lon == info.grid_lon &&
cache[i].grid.spacing == grid_spacing) {
cache[i].last_access_ms = hal.scheduler->millis();
cache[i].last_access_ms = AP_HAL::millis();
return cache[i];
}
if (cache[i].last_access_ms < cache[oldest_i].last_access_ms) {
@ -145,7 +145,7 @@ AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(const struct grid_info &info @@ -145,7 +145,7 @@ AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(const struct grid_info &info
grid.grid.lat_degrees = info.lat_degrees;
grid.grid.lon_degrees = info.lon_degrees;
grid.grid.version = TERRAIN_GRID_FORMAT_VERSION;
grid.last_access_ms = hal.scheduler->millis();
grid.last_access_ms = AP_HAL::millis();
// mark as waiting for disk read
grid.state = GRID_CACHE_DISKWAIT;

Loading…
Cancel
Save