mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Proximity: move location_update to Location and rename to offset_bearing
This commit is contained in:
parent
12a357ffd7
commit
72e4e69add
@ -107,7 +107,7 @@ bool AP_Proximity_SITL::get_distance_to_fence(float angle_deg, float &distance)
|
||||
while (max_dist - min_dist > PROXIMITY_ACCURACY) {
|
||||
float test_dist = (max_dist+min_dist)*0.5f;
|
||||
Location loc = current_loc;
|
||||
location_update(loc, angle_deg, test_dist);
|
||||
loc.offset_bearing(angle_deg, test_dist);
|
||||
Vector2l vecloc(loc.lat, loc.lng);
|
||||
if (fence_loader.boundary_breached(vecloc, fence_count->get(), fence)) {
|
||||
max_dist = test_dist;
|
||||
|
@ -5,6 +5,7 @@
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
#include <AC_Fence/AC_PolyFence_loader.h>
|
||||
#include <AP_Common/Location.h>
|
||||
|
||||
class AP_Proximity_SITL : public AP_Proximity_Backend
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user