mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: fix example sketch
This commit is contained in:
parent
5fefce5899
commit
5cc26569fc
|
@ -109,7 +109,13 @@ void motor_order_test()
|
|||
{
|
||||
hal.console->println("testing motor order");
|
||||
motors.armed(true);
|
||||
motors.output_test();
|
||||
for (int8_t i=1; i <= AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
hal.console->printf_P(PSTR("Motor %d\n"),(int)i);
|
||||
motors.output_test(i, 1150);
|
||||
hal.scheduler->delay(300);
|
||||
motors.output_test(i, 1000);
|
||||
hal.scheduler->delay(2000);
|
||||
}
|
||||
motors.armed(false);
|
||||
hal.console->println("finished test.");
|
||||
|
||||
|
|
Loading…
Reference in New Issue