SITL_AirSim: moved NED position initialization

out of always false if -statement
This commit is contained in:
dmitry 2020-09-11 11:47:48 +03:00 committed by Andrew Tridgell
parent 4ed486bb92
commit 94d2f4ea0e
1 changed files with 2 additions and 1 deletions

View File

@ -307,6 +307,8 @@ void AirSim::recv_fdm(const sitl_input& input)
location.lng = state.gps.lon * 1.0e7;
location.alt = state.gps.alt * 100.0f;
position = home.get_distance_NED(location);
dcm.from_euler(state.pose.roll, state.pose.pitch, state.pose.yaw);
if (last_timestamp) {
@ -358,7 +360,6 @@ void AirSim::recv_fdm(const sitl_input& input)
degrees(gyro.z));
Vector3f velocity_bf = dcm.transposed() * velocity_ef;
position = home.get_distance_NED(location);
// @LoggerMessage: ASM2
// @Description: More AirSim simulation data