autotest: fixed motor order display

This commit is contained in:
Andrew Tridgell 2011-12-12 23:14:29 +11:00
parent a3403aeb6c
commit bb6e582ce7
1 changed files with 2 additions and 2 deletions

View File

@ -22,8 +22,8 @@ var update_quad = func( ) {
# airspeed-kt is actually in feet per second (FDM NET bug)
setprop("/apm/airspeed", round10(0.3048*getprop("/velocities/airspeed-kt")));
setprop("/apm/motor_left", round10(getprop("/engines/engine[0]/rpm")/10.0));
setprop("/apm/motor_right", round10(getprop("/engines/engine[1]/rpm")/10.0));
setprop("/apm/motor_right", round10(getprop("/engines/engine[0]/rpm")/10.0));
setprop("/apm/motor_left", round10(getprop("/engines/engine[1]/rpm")/10.0));
setprop("/apm/motor_front", round10(getprop("/engines/engine[2]/rpm")/10.0));
setprop("/apm/motor_back", round10(getprop("/engines/engine[3]/rpm")/10.0));
}