mirror of https://github.com/ArduPilot/ardupilot
Send lat lon in SIM_STATE as int32_t extensions
This commit is contained in:
parent
8c4d00e6f2
commit
40f62949b3
|
@ -1144,7 +1144,9 @@ void SIM::sim_state_send(mavlink_channel_t chan) const
|
||||||
0.0,
|
0.0,
|
||||||
state.speedN,
|
state.speedN,
|
||||||
state.speedE,
|
state.speedE,
|
||||||
state.speedD);
|
state.speedD,
|
||||||
|
(int32_t)(state.latitude*1.0e7),
|
||||||
|
(int32_t)(state.longitude*1.0e7));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* report SITL state to AP_Logger */
|
/* report SITL state to AP_Logger */
|
||||||
|
|
Loading…
Reference in New Issue