From c518f8c224982f686d4efae5bafeaed7bc85d214 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 13 Dec 2011 15:27:32 +1100 Subject: [PATCH] autotest: show groundspeed in flightgear display useful with wind --- Tools/autotest/aircraft/Rascal/Rascal110-JSBSim-set.xml | 1 + Tools/autotest/aircraft/Rascal/Systems/airdata.nas | 3 +++ 2 files changed, 4 insertions(+) diff --git a/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim-set.xml b/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim-set.xml index dacac84190..12c2e019e8 100644 --- a/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim-set.xml +++ b/Tools/autotest/aircraft/Rascal/Rascal110-JSBSim-set.xml @@ -134,6 +134,7 @@ dynamics model, and external 3D model. right.add("/apm/altitude"); right.add("/apm/heading"); right.add("/apm/airspeed"); + right.add("/apm/groundspeed"); }); diff --git a/Tools/autotest/aircraft/Rascal/Systems/airdata.nas b/Tools/autotest/aircraft/Rascal/Systems/airdata.nas index 99bc911620..f68112d12d 100644 --- a/Tools/autotest/aircraft/Rascal/Systems/airdata.nas +++ b/Tools/autotest/aircraft/Rascal/Systems/airdata.nas @@ -64,6 +64,9 @@ var update_vars = func( dt ) { setprop("/apm/elevator", round100(getprop("/surface-positions/elevator-pos-norm"))); setprop("/apm/rudder", round100(getprop("/surface-positions/rudder-pos-norm"))); setprop("/apm/throttle", round10(getprop("/engines/engine/rpm"))); + + setprop("/apm/groundspeed", round10(0.514444444*getprop("/instrumentation/gps/indicated-ground-speed-kt"))); + # airspeed-kt is actually in feet per second (FDM NET bug) setprop("/apm/airspeed", round10(0.3048*getprop("/velocities/airspeed-kt"))); }