mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
uncrustify libraries/AP_Airspeed/AP_Airspeed.cpp
This commit is contained in:
parent
6c5f73fde4
commit
314b84f209
@ -1,12 +1,12 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
APM_Airspeed.cpp - airspeed (pitot) driver
|
||||
|
||||
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.
|
||||
*/
|
||||
* APM_Airspeed.cpp - airspeed (pitot) driver
|
||||
*
|
||||
* 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>
|
||||
@ -47,29 +47,29 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = {
|
||||
// the get_airspeed() interface can be used
|
||||
void AP_Airspeed::calibrate(void (*callback)(unsigned long t))
|
||||
{
|
||||
float sum = 0;
|
||||
uint8_t c;
|
||||
if (!_enable) {
|
||||
return;
|
||||
}
|
||||
_source->read();
|
||||
for (c = 0; c < 10; c++) {
|
||||
callback(100);
|
||||
sum += _source->read();
|
||||
}
|
||||
_airspeed_raw = sum/c;
|
||||
_offset.set_and_save(_airspeed_raw);
|
||||
_airspeed = 0;
|
||||
float sum = 0;
|
||||
uint8_t c;
|
||||
if (!_enable) {
|
||||
return;
|
||||
}
|
||||
_source->read();
|
||||
for (c = 0; c < 10; c++) {
|
||||
callback(100);
|
||||
sum += _source->read();
|
||||
}
|
||||
_airspeed_raw = sum/c;
|
||||
_offset.set_and_save(_airspeed_raw);
|
||||
_airspeed = 0;
|
||||
}
|
||||
|
||||
// read the airspeed sensor
|
||||
void AP_Airspeed::read(void)
|
||||
{
|
||||
float airspeed_pressure;
|
||||
if (!_enable) {
|
||||
return;
|
||||
}
|
||||
_airspeed_raw = _source->read();
|
||||
airspeed_pressure = max((_airspeed_raw - _offset), 0);
|
||||
_airspeed = sqrt(airspeed_pressure * _ratio);
|
||||
float airspeed_pressure;
|
||||
if (!_enable) {
|
||||
return;
|
||||
}
|
||||
_airspeed_raw = _source->read();
|
||||
airspeed_pressure = max((_airspeed_raw - _offset), 0);
|
||||
_airspeed = sqrt(airspeed_pressure * _ratio);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user