mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
8fb7098903
This commit changes the way libraries headers are included in source files: - If the header is in the same directory the source belongs to, so the notation '#include ""' is used with the path relative to the directory containing the source. - If the header is outside the directory containing the source, then we use the notation '#include <>' with the path relative to libraries folder. Some of the advantages of such approach: - Only one search path for libraries headers. - OSs like Windows may have a better lookup time.
60 lines
1.6 KiB
C++
60 lines
1.6 KiB
C++
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
/*
|
|
This program is free software: you can redistribute it and/or modify
|
|
it under the terms of the GNU General Public License as published by
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
(at your option) any later version.
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
GNU General Public License for more details.
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
*/
|
|
/*
|
|
* analog airspeed driver
|
|
*/
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include <AP_Math/AP_Math.h>
|
|
#include <AP_Common/AP_Common.h>
|
|
#include <AP_ADC/AP_ADC.h>
|
|
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
|
#include "AP_Airspeed.h"
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
// scaling for 3DR analog airspeed sensor
|
|
#define VOLTS_TO_PASCAL 819
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
extern AP_ADC_ADS7844 apm1_adc;
|
|
#endif
|
|
|
|
bool AP_Airspeed_Analog::init()
|
|
{
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
if (_pin == 64) {
|
|
_source = new AP_ADC_AnalogSource( &apm1_adc, 7, 1.0f);
|
|
return true;
|
|
}
|
|
#endif
|
|
_source = hal.analogin->channel(_pin);
|
|
return true;
|
|
}
|
|
|
|
// read the airspeed sensor
|
|
bool AP_Airspeed_Analog::get_differential_pressure(float &pressure)
|
|
{
|
|
if (_source == NULL) {
|
|
return false;
|
|
}
|
|
_source->set_pin(_pin);
|
|
pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL;
|
|
return true;
|
|
}
|
|
|