Browse Source

AP_Terrain: fix snprintf buffer length warning

Also includes fix from Tridge to use MIN() instead of MAX()
master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
adde7bc588
  1. 4
      libraries/AP_Terrain/TerrainIO.cpp

4
libraries/AP_Terrain/TerrainIO.cpp

@ -173,9 +173,9 @@ void AP_Terrain::open_file(void) @@ -173,9 +173,9 @@ void AP_Terrain::open_file(void)
}
snprintf(p, 13, "/%c%02u%c%03u.DAT",
block.lat_degrees<0?'S':'N',
abs((int32_t)block.lat_degrees),
MIN(abs((int32_t)block.lat_degrees), 99),
block.lon_degrees<0?'W':'E',
abs((int32_t)block.lon_degrees));
MIN(abs((int32_t)block.lon_degrees), 999));
// create directory if need be
if (!directory_created) {

Loading…
Cancel
Save