From 12497c51b5f12dc9ab4bea553f139682048ba74e Mon Sep 17 00:00:00 2001 From: uncrustify Date: Thu, 16 Aug 2012 23:09:23 -0700 Subject: [PATCH] uncrustify libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde --- .../AP_Baro_MS5611_test.pde | 68 +++++++++---------- 1 file changed, 34 insertions(+), 34 deletions(-) diff --git a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde index 3f74bbe4bc..8f1ecc13f2 100644 --- a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde +++ b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde @@ -2,7 +2,7 @@ #include #include #include -#include // ArduPilot Mega Vector/Matrix math Library +#include // ArduPilot Mega Vector/Matrix math Library #include #include #include @@ -14,50 +14,50 @@ FastSerialPort0(Serial); AP_Baro_MS5611 baro; Arduino_Mega_ISR_Registry isr_registry; -AP_TimerProcess scheduler; +AP_TimerProcess scheduler; unsigned long timer; void setup() { - Serial.begin(115200, 128, 128); - Serial.println("ArduPilot Mega MeasSense Barometer library test"); + Serial.begin(115200, 128, 128); + Serial.println("ArduPilot Mega MeasSense Barometer library test"); - delay(1000); + delay(1000); - isr_registry.init(); - scheduler.init(&isr_registry); + isr_registry.init(); + scheduler.init(&isr_registry); - pinMode(63, OUTPUT); - digitalWrite(63, HIGH); - SPI.begin(); - SPI.setClockDivider(SPI_CLOCK_DIV32); // 500khz for debugging, increase later + pinMode(63, OUTPUT); + digitalWrite(63, HIGH); + SPI.begin(); + SPI.setClockDivider(SPI_CLOCK_DIV32); // 500khz for debugging, increase later - baro.init(&scheduler); - baro.calibrate(delay); - timer = millis(); + baro.init(&scheduler); + baro.calibrate(delay); + timer = millis(); } void loop() { - if((micros() - timer) > 100000UL){ - timer = micros(); - baro.read(); - uint32_t read_time = micros() - timer; - if (!baro.healthy) { - Serial.println("not healthy"); - return; - } - Serial.print("Pressure:"); - Serial.print(baro.get_pressure()); - Serial.print(" Temperature:"); - Serial.print(baro.get_temperature()); - Serial.print(" Altitude:"); - Serial.print(baro.get_altitude()); - Serial.printf(" climb=%.2f t=%u samples=%u", - baro.get_climb_rate(), - (unsigned)read_time, - (unsigned)baro.get_pressure_samples()); - Serial.println(); - } + if((micros() - timer) > 100000UL) { + timer = micros(); + baro.read(); + uint32_t read_time = micros() - timer; + if (!baro.healthy) { + Serial.println("not healthy"); + return; + } + Serial.print("Pressure:"); + Serial.print(baro.get_pressure()); + Serial.print(" Temperature:"); + Serial.print(baro.get_temperature()); + Serial.print(" Altitude:"); + Serial.print(baro.get_altitude()); + Serial.printf(" climb=%.2f t=%u samples=%u", + baro.get_climb_rate(), + (unsigned)read_time, + (unsigned)baro.get_pressure_samples()); + Serial.println(); + } }