mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_Terrain: move location_update to Location and rename to offset_bearing
This commit is contained in:
parent
3e122c19f3
commit
58cd9361cb
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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…
Reference in New Issue
Block a user