From 2d9637c156bb186660fe623bfd98c7fce8290ce8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 23 Jul 2014 12:19:29 +1000 Subject: [PATCH] AP_Terrain: re-arrange disk IO code add some comments explaining split between IO thread and main code --- libraries/AP_Terrain/AP_Terrain.cpp | 49 +++++++++++++++++------------ libraries/AP_Terrain/AP_Terrain.h | 5 +++ 2 files changed, 34 insertions(+), 20 deletions(-) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 50d2a7718a..c67ba1ee5a 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -304,7 +304,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan) } // see if we need to schedule some disk IO - update(); + schedule_disk_io(); // did we request recently? if (hal.scheduler->millis() - last_request_time_ms < 2000) { @@ -547,10 +547,9 @@ void AP_Terrain::check_disk_write(void) } /* - update terrain data. Check if we need to do disk IO for grids. This - should be called at around 1Hz + Check if we need to do disk IO for grids. */ -void AP_Terrain::update(void) +void AP_Terrain::schedule_disk_io(void) { if (enable == 0) { return; @@ -604,24 +603,18 @@ void AP_Terrain::update(void) // waiting for io_timer() break; } - - Location loc; - if (!ahrs.get_position(loc)) { - // we don't know where we are - return; - } - -#if TERRAIN_DEBUG - static uint32_t last_report_ms; - float height; - - if (hal.scheduler->millis() - last_report_ms > 1000 && height_amsl(loc, height)) { - printf("height %.2f\n", height); - last_report_ms = hal.scheduler->millis(); - } -#endif } +/* + 1Hz update function. This is here to ensure progress is made on disk + IO even if no MAVLink send_request() operations are called for a + while. + */ +void AP_Terrain::update(void) +{ + // just schedule any needed disk IO + schedule_disk_io(); +} /* get CRC for a block @@ -635,6 +628,22 @@ uint16_t AP_Terrain::get_block_crc(struct grid_block &block) return ret; } + +/******************************************************** +All the functions below this point run in the IO timer +context, which is a separate thread. The code uses the state +machine controlled by disk_io_state to manage who has +access to the structures and to prevent race conditions. + +The IO timer context owns the data when disk_io_state is +DiskIoWaitWrite or DiskIoWaitRead. The main thread owns the +data when disk_io_state is DiskIoIdle, DiskIoDoneWrite or +DiskIoDoneRead + +All file operations are done by the IO thread. +*********************************************************/ + + /* open the current degree file */ diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 402822ca7c..e0f822c254 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -212,6 +212,11 @@ private: bool request_missing(mavlink_channel_t chan, struct grid_cache &gcache); bool request_missing(mavlink_channel_t chan, const struct grid_info &info); + /* + look for blocks that need to be read/written to disk + */ + void schedule_disk_io(void); + /* get some statistics for TERRAIN_REPORT */