mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Motors: example uses millis/micros/panic functions
This commit is contained in:
parent
01e4265ce1
commit
513f4fe986
@ -96,9 +96,9 @@ void motor_order_test()
|
||||
for (int8_t i=1; i <= 4; i++) {
|
||||
hal.console->printf("Motor %d\n",(int)i);
|
||||
int elapsed =0,stop;
|
||||
int start = hal.scheduler->micros(); //Time Test
|
||||
int start = AP_HAL::micros(); //Time Test
|
||||
motors.output_test(i, 1150);
|
||||
stop = hal.scheduler->micros();
|
||||
stop = AP_HAL::micros();
|
||||
elapsed = stop - start;
|
||||
hal.console->printf(" Elapsed Time: %dus\n",elapsed);
|
||||
hal.scheduler->delay(300);
|
||||
|
Loading…
Reference in New Issue
Block a user