From abc57740ee616513de6e953650879bd32e484315 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 29 Jan 2022 20:57:47 +1100 Subject: [PATCH] AP Avoidance: stop using relative_lat member in Location object --- libraries/AP_Avoidance/AP_Avoidance.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index 1362e7aaea..baac68d4f2 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -593,11 +593,12 @@ void AP_Avoidance::handle_msg(const mavlink_message_t &msg) // inform AP_Avoidance we have a new player mavlink_global_position_int_t packet; mavlink_msg_global_position_int_decode(&msg, &packet); - Location loc; - loc.lat = packet.lat; - loc.lng = packet.lon; - loc.alt = packet.alt / 10; // mm -> cm - loc.relative_alt = false; + const Location loc { + packet.lat, + packet.lon, + int32_t(packet.alt * 0.1), // mm -> cm + Location::AltFrame::ABSOLUTE + }; Vector3f vel = Vector3f(packet.vx/100.0f, // cm to m packet.vy/100.0f, packet.vz/100.0f);