SITL: Send VCAS in Flightgear packet.

This commit is contained in:
Samuel Tabor 2022-08-25 14:30:02 +01:00 committed by Tom Pittenger
parent 5586f4ad3a
commit 49fb4f37c5
1 changed files with 1 additions and 0 deletions

View File

@ -519,6 +519,7 @@ void SITL_State::_output_to_flightgear(void)
fdm.phi = radians(sfdm.rollDeg);
fdm.theta = radians(sfdm.pitchDeg);
fdm.psi = radians(sfdm.yawDeg);
fdm.vcas = sfdm.velocity_air_bf.length()/0.3048;
if (_vehicle == ArduCopter) {
fdm.num_engines = 4;
for (uint8_t i=0; i<4; i++) {