mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: example sketch output limit flags
This commit is contained in:
parent
c9055ccdb1
commit
bc1b8f415a
|
@ -146,11 +146,11 @@ void stability_test()
|
|||
motors.set_interlock(true);
|
||||
|
||||
#if NUM_OUTPUTS <= 4
|
||||
hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,AvgOut\n"); // quad
|
||||
hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,AvgOut,LimRP,LimY,LimThD,LimThU\n"); // quad
|
||||
#elif NUM_OUTPUTS <= 6
|
||||
hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,AvgOut\n"); // hexa
|
||||
hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,AvgOut,LimRP,LimY,LimThD,LimThU\n"); // hexa
|
||||
#else
|
||||
hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,Mot7,Mot8,AvgOut\n"); // octa
|
||||
hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,Mot7,Mot8,AvgOut,LimRP,LimY,LimThD,LimThU\n"); // octa
|
||||
#endif
|
||||
|
||||
// run stability test
|
||||
|
@ -174,11 +174,11 @@ void stability_test()
|
|||
avg_out = ((hal.rcout->read(0) + hal.rcout->read(1) + hal.rcout->read(2) + hal.rcout->read(3))/4);
|
||||
// display input and output
|
||||
#if NUM_OUTPUTS <= 4
|
||||
hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d\n", // quad
|
||||
hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d\n", // quad
|
||||
#elif NUM_OUTPUTS <= 6
|
||||
hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d\n", // hexa
|
||||
hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d\n", // hexa
|
||||
#else
|
||||
hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d\n", // octa
|
||||
hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d\n", // octa
|
||||
#endif
|
||||
(int)roll_in,
|
||||
(int)pitch_in,
|
||||
|
@ -196,7 +196,11 @@ void stability_test()
|
|||
(int)hal.rcout->read(6),
|
||||
(int)hal.rcout->read(7),
|
||||
#endif
|
||||
(int)avg_out);
|
||||
(int)avg_out,
|
||||
(int)motors.limit.roll_pitch,
|
||||
(int)motors.limit.yaw,
|
||||
(int)motors.limit.throttle_lower,
|
||||
(int)motors.limit.throttle_upper);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue