mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Terrain: use get_distance_NE instead of location_diff
This commit is contained in:
parent
51437ccc53
commit
6fbcb21ae3
@ -231,7 +231,7 @@ void AP_Terrain::seek_offset(void)
|
||||
|
||||
// shift another two blocks east to ensure room is available
|
||||
loc2.offset(0, 2*grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);
|
||||
Vector2f offset = location_diff(loc1, loc2);
|
||||
const Vector2f offset = loc1.get_distance_NE(loc2);
|
||||
uint16_t east_blocks = offset.y / (grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);
|
||||
|
||||
uint32_t file_offset = (east_blocks * block.grid_idx_x +
|
||||
|
@ -79,7 +79,7 @@ void AP_Terrain::calculate_grid_info(const Location &loc, struct grid_info &info
|
||||
ref.lng = info.lon_degrees*10*1000*1000L;
|
||||
|
||||
// find offset from reference
|
||||
Vector2f offset = location_diff(ref, loc);
|
||||
const Vector2f offset = ref.get_distance_NE(loc);
|
||||
|
||||
// get indices in terms of grid_spacing elements
|
||||
uint32_t idx_x = offset.x / grid_spacing;
|
||||
|
Loading…
Reference in New Issue
Block a user