From ebdcfdf65bc6b95c54d0f04f0c06186aa5270946 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Mon, 8 Apr 2019 15:16:20 +0200 Subject: [PATCH] SITL: use get_distance_NE instead of location_diff --- libraries/SITL/SIM_CRRCSim.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_CRRCSim.cpp b/libraries/SITL/SIM_CRRCSim.cpp index 43498b4117..39059754f6 100644 --- a/libraries/SITL/SIM_CRRCSim.cpp +++ b/libraries/SITL/SIM_CRRCSim.cpp @@ -122,7 +122,7 @@ void CRRCSim::recv_fdm(const struct sitl_input &input) Location loc1, loc2; loc2.lat = pkt.latitude * 1.0e7; loc2.lng = pkt.longitude * 1.0e7; - Vector2f posdelta = location_diff(loc1, loc2); + const Vector2f posdelta = loc1.get_distance_NE(loc2); position.x = posdelta.x; position.y = posdelta.y; position.z = -pkt.altitude;