Browse Source

InertialSensor: add reboot option in MPU6000 test

mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
0adc4afcb5
  1. 7
      libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde

7
libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde

@ -64,7 +64,8 @@ void loop(void) @@ -64,7 +64,8 @@ void loop(void)
" c) calibrate accelerometers\r\n"
" d) display offsets and scaling\r\n"
" l) level (capture offsets from level)\r\n"
" t) test"));
" t) test\r\n"
" r) reboot"));
// wait for user input
while( !hal.console->available() ) {
@ -92,6 +93,10 @@ void loop(void) @@ -92,6 +93,10 @@ void loop(void)
if( user_input == 't' || user_input == 'T' ) {
run_test();
}
if( user_input == 'r' || user_input == 'R' ) {
hal.scheduler->reboot();
}
}
}

Loading…
Cancel
Save