Browse Source

AP_Terrain: move location_update to Location and rename to offset_bearing

master
Pierre Kancir 6 years ago committed by Peter Barker
parent
commit
58cd9361cb
  1. 2
      libraries/AP_Terrain/AP_Terrain.cpp
  2. 1
      libraries/AP_Terrain/AP_Terrain.h
  3. 2
      libraries/AP_Terrain/TerrainMission.cpp

2
libraries/AP_Terrain/AP_Terrain.cpp

@ -271,7 +271,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio) @@ -271,7 +271,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
// check for terrain at grid spacing intervals
while (distance > 0) {
location_update(loc, bearing, grid_spacing);
loc.offset_bearing(bearing, grid_spacing);
climb += climb_ratio * grid_spacing;
distance -= grid_spacing;
float height;

1
libraries/AP_Terrain/AP_Terrain.h

@ -17,6 +17,7 @@ @@ -17,6 +17,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Common/Location.h>
#if (HAL_OS_POSIX_IO || HAL_OS_FATFS_IO) && defined(HAL_BOARD_TERRAIN_DIRECTORY)
#define AP_TERRAIN_AVAILABLE 1

2
libraries/AP_Terrain/TerrainMission.cpp

@ -82,7 +82,7 @@ void AP_Terrain::update_mission_data(void) @@ -82,7 +82,7 @@ void AP_Terrain::update_mission_data(void)
// spacings away at 45, 135, 225 and 315 degrees, and the
// point itself
if (next_mission_pos != 4) {
location_update(cmd.content.location, 45+90*next_mission_pos, grid_spacing.get() * 10);
cmd.content.location.offset_bearing(45+90*next_mission_pos, grid_spacing.get() * 10);
}
// we have a mission command to check

Loading…
Cancel
Save