uncrustify libraries/AP_Airspeed/examples/Airspeed/Airspeed.pde

This commit is contained in:
uncrustify 2012-08-16 23:08:43 -07:00 committed by Pat Hickey
parent d6d7606c84
commit 3c2873b4f5

View File

@ -1,12 +1,12 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
Airspeed.pde - airspeed example sketch
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public License
as published by the Free Software Foundation; either version 2.1
of the License, or (at your option) any later version.
*/
* Airspeed.pde - airspeed example sketch
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation; either version 2.1
* of the License, or (at your option) any later version.
*/
#include <FastSerial.h>
#include <AP_Common.h>
@ -19,7 +19,7 @@
#include <AP_Airspeed.h>
Arduino_Mega_ISR_Registry isr_registry;
AP_TimerProcess scheduler;
AP_TimerProcess scheduler;
FastSerialPort0(Serial);
@ -28,24 +28,24 @@ AP_Airspeed airspeed(&pin0, 1.9936, true);
void setup()
{
Serial.begin(115200, 128, 128);
Serial.println("ArduPilot Airspeed library test");
Serial.begin(115200, 128, 128);
Serial.println("ArduPilot Airspeed library test");
isr_registry.init();
scheduler.init(&isr_registry);
AP_AnalogSource_Arduino::init_timer(&scheduler);
isr_registry.init();
scheduler.init(&isr_registry);
AP_AnalogSource_Arduino::init_timer(&scheduler);
pinMode(0, INPUT);
pinMode(0, INPUT);
airspeed.calibrate(delay);
airspeed.calibrate(delay);
}
void loop(void)
{
static uint32_t timer;
if((millis() - timer) > 100){
timer = millis();
airspeed.read();
Serial.printf("airspeed %.2f\n", airspeed.get_airspeed());
}
static uint32_t timer;
if((millis() - timer) > 100) {
timer = millis();
airspeed.read();
Serial.printf("airspeed %.2f\n", airspeed.get_airspeed());
}
}