12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include "AP_Airspeed.h"
- class AP_Airspeed_Backend {
- public:
- AP_Airspeed_Backend(AP_Airspeed &frontend, uint8_t instance);
- virtual ~AP_Airspeed_Backend();
-
-
- virtual bool init(void) = 0;
-
- virtual bool get_differential_pressure(float &pressure) = 0;
-
- virtual bool get_temperature(float &temperature) = 0;
- protected:
- int8_t get_pin(void) const;
- float get_psi_range(void) const;
- uint8_t get_bus(void) const;
- AP_Airspeed::pitot_tube_order get_tube_order(void) const {
- return AP_Airspeed::pitot_tube_order(frontend.param[instance].tube_order.get());
- }
-
-
- HAL_Semaphore sem;
- float get_airspeed_ratio(void) const {
- return frontend.get_airspeed_ratio(instance);
- }
-
- void set_use_zero_offset(void) {
- frontend.state[instance].use_zero_offset = true;
- }
-
- void set_skip_cal(void) {
- frontend.param[instance].skip_cal.set(1);
- }
-
- void set_offset(float ofs) {
- frontend.param[instance].offset.set(ofs);
- }
-
- private:
- AP_Airspeed &frontend;
- uint8_t instance;
- };
|