From 0aa520a2738de1c2f0e6ae327a089547e2d1e7f2 Mon Sep 17 00:00:00 2001 From: Caio Marcelo de Oliveira Filho Date: Fri, 20 Nov 2015 12:14:56 +0900 Subject: [PATCH] AP_Terrain: use millis/micros/panic functions --- libraries/AP_Terrain/AP_Terrain.cpp | 2 +- libraries/AP_Terrain/TerrainGCS.cpp | 4 ++-- libraries/AP_Terrain/TerrainIO.cpp | 2 +- libraries/AP_Terrain/TerrainUtil.cpp | 4 ++-- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index bf01d86aa4..ea5e5d5c19 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -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, diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index 5f4e5bb73b..80a6428e2a 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -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) 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; } diff --git a/libraries/AP_Terrain/TerrainIO.cpp b/libraries/AP_Terrain/TerrainIO.cpp index b6a72da34e..ae6f31aab1 100644 --- a/libraries/AP_Terrain/TerrainIO.cpp +++ b/libraries/AP_Terrain/TerrainIO.cpp @@ -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; diff --git a/libraries/AP_Terrain/TerrainUtil.cpp b/libraries/AP_Terrain/TerrainUtil.cpp index 0de487179e..7a855f2b9d 100644 --- a/libraries/AP_Terrain/TerrainUtil.cpp +++ b/libraries/AP_Terrain/TerrainUtil.cpp @@ -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 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;