Browse Source

AP_Motors: fix example sketch

master
Randy Mackay 11 years ago
parent
commit
5cc26569fc
  1. 8
      libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde

8
libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde

@ -109,7 +109,13 @@ void motor_order_test() @@ -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…
Cancel
Save