mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
SITL: fixed airspeed in CRRCSim
This commit is contained in:
parent
da5d5c9936
commit
ae6ac1b82d
@ -129,8 +129,7 @@ void CRRCSim::recv_fdm(const struct sitl_input &input)
|
|||||||
position.y = posdelta.y;
|
position.y = posdelta.y;
|
||||||
position.z = -pkt.altitude;
|
position.z = -pkt.altitude;
|
||||||
|
|
||||||
// assume zero wind for now
|
airspeed = pkt.airspeed;
|
||||||
airspeed = velocity_ef.length();
|
|
||||||
|
|
||||||
dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw);
|
dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user