Browse Source

SITL: use get_distance_NE instead of location_diff

master
Pierre Kancir 6 years ago committed by Tom Pittenger
parent
commit
ebdcfdf65b
  1. 2
      libraries/SITL/SIM_CRRCSim.cpp

2
libraries/SITL/SIM_CRRCSim.cpp

@ -122,7 +122,7 @@ void CRRCSim::recv_fdm(const struct sitl_input &input)
Location loc1, loc2; Location loc1, loc2;
loc2.lat = pkt.latitude * 1.0e7; loc2.lat = pkt.latitude * 1.0e7;
loc2.lng = pkt.longitude * 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.x = posdelta.x;
position.y = posdelta.y; position.y = posdelta.y;
position.z = -pkt.altitude; position.z = -pkt.altitude;

Loading…
Cancel
Save