From 0adc4afcb5df28f8ad91c47eb02d9790ce83addd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 27 Dec 2012 21:29:00 +1100 Subject: [PATCH] InertialSensor: add reboot option in MPU6000 test --- libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde b/libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde index 829ef87931..0afb122aa3 100644 --- a/libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde +++ b/libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde @@ -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) if( user_input == 't' || user_input == 'T' ) { run_test(); } + + if( user_input == 'r' || user_input == 'R' ) { + hal.scheduler->reboot(); + } } }