APM:Libraries
AP_Airspeed_analog.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  * analog airspeed driver
17  */
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include <AP_Common/AP_Common.h>
21 
22 #include "AP_Airspeed.h"
23 #include "AP_Airspeed_analog.h"
24 
25 extern const AP_HAL::HAL &hal;
26 
27 // scaling for 3DR analog airspeed sensor
28 #define VOLTS_TO_PASCAL 819
29 
30 AP_Airspeed_Analog::AP_Airspeed_Analog(AP_Airspeed &_frontend, uint8_t _instance) :
31  AP_Airspeed_Backend(_frontend, _instance)
32 {
33  _source = hal.analogin->channel(get_pin());
34 }
35 
37 {
38  return _source != nullptr;
39 }
40 
41 // read the airspeed sensor
43 {
44  if (_source == nullptr) {
45  return false;
46  }
47  // allow pin to change
50  return true;
51 }
float get_psi_range(void) const
#define VOLTS_TO_PASCAL
int8_t get_pin(void) const
AP_Airspeed_Analog(AP_Airspeed &frontend, uint8_t _instance)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool init(void) override
AP_HAL::AnalogSource * _source
Common definitions and utility routines for the ArduPilot libraries.
bool get_differential_pressure(float &pressure) override
virtual void set_pin(uint8_t p)=0
virtual float voltage_average_ratiometric()=0
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
virtual AP_HAL::AnalogSource * channel(int16_t n)=0