123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051 |
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Common/AP_Common.h>
- #include "AP_Airspeed.h"
- #include "AP_Airspeed_analog.h"
- extern const AP_HAL::HAL &hal;
- #define VOLTS_TO_PASCAL 819
- AP_Airspeed_Analog::AP_Airspeed_Analog(AP_Airspeed &_frontend, uint8_t _instance) :
- AP_Airspeed_Backend(_frontend, _instance)
- {
- _source = hal.analogin->channel(get_pin());
- }
- bool AP_Airspeed_Analog::init()
- {
- return _source != nullptr;
- }
- bool AP_Airspeed_Analog::get_differential_pressure(float &pressure)
- {
- if (_source == nullptr) {
- return false;
- }
-
- _source->set_pin(get_pin());
- pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL / get_psi_range();
- return true;
- }
|