autotest: show groundspeed in flightgear display

useful with wind
This commit is contained in:
Andrew Tridgell 2011-12-13 15:27:32 +11:00
parent f96dca3311
commit c518f8c224
2 changed files with 4 additions and 0 deletions

View File

@ -134,6 +134,7 @@ dynamics model, and external 3D model.
right.add("/apm/altitude"); right.add("/apm/altitude");
right.add("/apm/heading"); right.add("/apm/heading");
right.add("/apm/airspeed"); right.add("/apm/airspeed");
right.add("/apm/groundspeed");
}); });
</script> </script>
</rascal> </rascal>

View File

@ -64,6 +64,9 @@ var update_vars = func( dt ) {
setprop("/apm/elevator", round100(getprop("/surface-positions/elevator-pos-norm"))); setprop("/apm/elevator", round100(getprop("/surface-positions/elevator-pos-norm")));
setprop("/apm/rudder", round100(getprop("/surface-positions/rudder-pos-norm"))); setprop("/apm/rudder", round100(getprop("/surface-positions/rudder-pos-norm")));
setprop("/apm/throttle", round10(getprop("/engines/engine/rpm"))); 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) # airspeed-kt is actually in feet per second (FDM NET bug)
setprop("/apm/airspeed", round10(0.3048*getprop("/velocities/airspeed-kt"))); setprop("/apm/airspeed", round10(0.3048*getprop("/velocities/airspeed-kt")));
} }