mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
autotest: nicer display of key data in Rascal
This commit is contained in:
parent
b51782d42c
commit
e0d7e7cf0b
@ -123,16 +123,17 @@ dynamics model, and external 3D model.
|
|||||||
<script>
|
<script>
|
||||||
setlistener("/sim/signals/fdm-initialized", func {
|
setlistener("/sim/signals/fdm-initialized", func {
|
||||||
var left = screen.display.new(20, 10);
|
var left = screen.display.new(20, 10);
|
||||||
left.add("/surface-positions/right-aileron-pos-norm");
|
left.add("/apm/aileron");
|
||||||
left.add("/surface-positions/elevator-pos-norm");
|
left.add("/apm/elevator");
|
||||||
left.add("/surface-positions/rudder-pos-norm");
|
left.add("/apm/rudder");
|
||||||
left.add("/engines/engine/rpm");
|
left.add("/apm/throttle");
|
||||||
|
|
||||||
var right = screen.display.new(-250, 20);
|
var right = screen.display.new(-250, 20);
|
||||||
right.add("/orientation/pitch-deg");
|
right.add("/apm/pitch");
|
||||||
right.add("/orientation/roll-deg");
|
right.add("/apm/roll");
|
||||||
right.add("/position/altitude-agl-ft");
|
right.add("/apm/altitude");
|
||||||
right.add("/velocities/airspeed-kt");
|
right.add("/apm/heading");
|
||||||
|
right.add("/apm/airspeed");
|
||||||
});
|
});
|
||||||
</script>
|
</script>
|
||||||
</rascal>
|
</rascal>
|
||||||
|
@ -38,3 +38,32 @@ var update_airdata = func( dt ) {
|
|||||||
|
|
||||||
setprop("/accelerations/airspeed-ktps", accel_filt);
|
setprop("/accelerations/airspeed-ktps", accel_filt);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
round10 = func(v) {
|
||||||
|
if (v == nil) return 0;
|
||||||
|
return 0.1*int(v*10);
|
||||||
|
}
|
||||||
|
|
||||||
|
round100 = func(v) {
|
||||||
|
if (v == nil) return 0;
|
||||||
|
return 0.01*int(v*100);
|
||||||
|
}
|
||||||
|
|
||||||
|
var update_vars = func( dt ) {
|
||||||
|
asl_ft = getprop("/position/altitude-ft");
|
||||||
|
ground = getprop("/position/ground-elev-ft");
|
||||||
|
agl_m = (asl_ft - ground) * 0.3048;
|
||||||
|
|
||||||
|
setprop("/apm/altitude", round10(agl_m));
|
||||||
|
|
||||||
|
setprop("/apm/pitch", round10(getprop("/orientation/pitch-deg")));
|
||||||
|
setprop("/apm/roll", round10(getprop("/orientation/roll-deg")));
|
||||||
|
setprop("/apm/heading", round10(getprop("/orientation/heading-deg")));
|
||||||
|
|
||||||
|
setprop("/apm/aileron", round100(getprop("/surface-positions/right-aileron-pos-norm")));
|
||||||
|
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")));
|
||||||
|
# airspeed-kt is actually in feet per second (FDM NET bug)
|
||||||
|
setprop("/apm/airspeed", round10(0.3048*getprop("/velocities/airspeed-kt")));
|
||||||
|
}
|
||||||
|
@ -10,6 +10,7 @@ var main_loop = func {
|
|||||||
last_time = time;
|
last_time = time;
|
||||||
|
|
||||||
update_airdata( dt );
|
update_airdata( dt );
|
||||||
|
update_vars( dt );
|
||||||
update_ugear( dt );
|
update_ugear( dt );
|
||||||
|
|
||||||
settimer(main_loop, 0);
|
settimer(main_loop, 0);
|
||||||
|
Loading…
Reference in New Issue
Block a user