AP_Terrain: replace location_offset() and get_distance() function calls with Location object member function calls

This allows removing duplicated code
This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2019-02-25 01:16:28 +01:00 committed by Peter Barker
parent 31a32c7ea0
commit 6082b230e8
3 changed files with 6 additions and 8 deletions

View File

@ -118,9 +118,8 @@ void AP_Terrain::send_request(mavlink_channel_t chan)
for (int8_t x=-1; x<=1; x++) {
for (int8_t y=-1; y<=1; y++) {
Location loc2 = loc;
location_offset(loc2,
x*TERRAIN_GRID_BLOCK_SIZE_X*0.7f*grid_spacing,
y*TERRAIN_GRID_BLOCK_SIZE_Y*0.7f*grid_spacing);
loc2.offset(x*TERRAIN_GRID_BLOCK_SIZE_X*0.7f*grid_spacing,
y*TERRAIN_GRID_BLOCK_SIZE_Y*0.7f*grid_spacing);
struct grid_info info2;
calculate_grid_info(loc2, info2);
if (request_missing(chan, info2)) {
@ -301,7 +300,7 @@ void AP_Terrain::handle_terrain_data(mavlink_message_t *msg)
Location loc2;
loc2.lat = grid.lat;
loc2.lng = grid.lon;
location_offset(loc2, 28*grid_spacing, 32*grid_spacing);
loc2.offset(28*grid_spacing, 32*grid_spacing);
hal.console->printf("--lat=%12.7f --lon=%12.7f %u\n",
loc2.lat*1.0e-7f,
loc2.lng*1.0e-7f,

View File

@ -230,7 +230,7 @@ void AP_Terrain::seek_offset(void)
loc2.lng = (block.lon_degrees+1)*10*1000*1000L;
// shift another two blocks east to ensure room is available
location_offset(loc2, 0, 2*grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);
loc2.offset(0, 2*grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);
Vector2f offset = location_diff(loc1, loc2);
uint16_t east_blocks = offset.y / (grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);

View File

@ -100,9 +100,8 @@ void AP_Terrain::calculate_grid_info(const Location &loc, struct grid_info &info
info.frac_y = (offset.y - idx_y * grid_spacing) / grid_spacing;
// calculate lat/lon of SW corner of 32*28 grid_block
location_offset(ref,
info.grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * (float)grid_spacing,
info.grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * (float)grid_spacing);
ref.offset(info.grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * (float)grid_spacing,
info.grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * (float)grid_spacing);
info.grid_lat = ref.lat;
info.grid_lon = ref.lng;