mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_InertialSensor: examples: add coding style fixes
Several coding style problems were already fixed by previous commit, just finish the cleanup on this example: - replace tabs with spaces - remove unneeded \r - remove extra spaces
This commit is contained in:
parent
10e7d43007
commit
f304fcf4da
@ -9,7 +9,7 @@
|
|||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
@ -39,31 +39,31 @@ void loop(void)
|
|||||||
|
|
||||||
hal.console->println();
|
hal.console->println();
|
||||||
hal.console->println(
|
hal.console->println(
|
||||||
"Menu:\r\n"
|
"Menu:\n"
|
||||||
" d) display offsets and scaling\r\n"
|
" d) display offsets and scaling\n"
|
||||||
" l) level (capture offsets from level)\r\n"
|
" l) level (capture offsets from level)\n"
|
||||||
" t) test\r\n"
|
" t) test\n"
|
||||||
" r) reboot");
|
" r) reboot");
|
||||||
|
|
||||||
// wait for user input
|
// wait for user input
|
||||||
while( !hal.console->available() ) {
|
while (!hal.console->available()) {
|
||||||
hal.scheduler->delay(20);
|
hal.scheduler->delay(20);
|
||||||
}
|
}
|
||||||
|
|
||||||
// read in user input
|
// read in user input
|
||||||
while( hal.console->available() ) {
|
while (hal.console->available()) {
|
||||||
user_input = hal.console->read();
|
user_input = hal.console->read();
|
||||||
|
|
||||||
if( user_input == 'd' || user_input == 'D' ) {
|
if (user_input == 'd' || user_input == 'D') {
|
||||||
display_offsets_and_scaling();
|
display_offsets_and_scaling();
|
||||||
}
|
}
|
||||||
|
|
||||||
if( user_input == 't' || user_input == 'T' ) {
|
if (user_input == 't' || user_input == 'T') {
|
||||||
run_test();
|
run_test();
|
||||||
}
|
}
|
||||||
|
|
||||||
if( user_input == 'r' || user_input == 'R' ) {
|
if (user_input == 'r' || user_input == 'R') {
|
||||||
hal.scheduler->reboot(false);
|
hal.scheduler->reboot(false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -102,7 +102,7 @@ static void run_test()
|
|||||||
static uint8_t ins_count = MAX(accel_count, gyro_count);
|
static uint8_t ins_count = MAX(accel_count, gyro_count);
|
||||||
|
|
||||||
// flush any user input
|
// flush any user input
|
||||||
while( hal.console->available() ) {
|
while (hal.console->available()) {
|
||||||
hal.console->read();
|
hal.console->read();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -110,8 +110,7 @@ static void run_test()
|
|||||||
ins.update();
|
ins.update();
|
||||||
|
|
||||||
// loop as long as user does not press a key
|
// loop as long as user does not press a key
|
||||||
while( !hal.console->available() ) {
|
while (!hal.console->available()) {
|
||||||
|
|
||||||
// wait until we have a sample
|
// wait until we have a sample
|
||||||
ins.wait_for_sample();
|
ins.wait_for_sample();
|
||||||
|
|
||||||
@ -162,7 +161,7 @@ static void run_test()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// clear user input
|
// clear user input
|
||||||
while( hal.console->available() ) {
|
while (hal.console->available()) {
|
||||||
hal.console->read();
|
hal.console->read();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user