mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
SITL: fill in SIMSTATE.lat and SIMSTATE.lng
This commit is contained in:
parent
d46b7a67b7
commit
3419d8e006
@ -53,7 +53,9 @@ void SITL::simstate_send(mavlink_channel_t chan)
|
|||||||
state.xAccel,
|
state.xAccel,
|
||||||
state.yAccel,
|
state.yAccel,
|
||||||
state.zAccel,
|
state.zAccel,
|
||||||
p, q, r);
|
p, q, r,
|
||||||
|
state.latitude,
|
||||||
|
state.longitude);
|
||||||
}
|
}
|
||||||
|
|
||||||
// convert a set of roll rates from earth frame to body frame
|
// convert a set of roll rates from earth frame to body frame
|
||||||
|
Loading…
Reference in New Issue
Block a user