AP_Airspeed_Backend.h 2.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. /*
  15. backend driver class for airspeed
  16. */
  17. #include <AP_Common/AP_Common.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include "AP_Airspeed.h"
  20. class AP_Airspeed_Backend {
  21. public:
  22. AP_Airspeed_Backend(AP_Airspeed &frontend, uint8_t instance);
  23. virtual ~AP_Airspeed_Backend();
  24. // probe and initialise the sensor
  25. virtual bool init(void) = 0;
  26. // return the current differential_pressure in Pascal
  27. virtual bool get_differential_pressure(float &pressure) = 0;
  28. // return the current temperature in degrees C, if available
  29. virtual bool get_temperature(float &temperature) = 0;
  30. protected:
  31. int8_t get_pin(void) const;
  32. float get_psi_range(void) const;
  33. uint8_t get_bus(void) const;
  34. AP_Airspeed::pitot_tube_order get_tube_order(void) const {
  35. return AP_Airspeed::pitot_tube_order(frontend.param[instance].tube_order.get());
  36. }
  37. // semaphore for access to shared frontend data
  38. HAL_Semaphore sem;
  39. float get_airspeed_ratio(void) const {
  40. return frontend.get_airspeed_ratio(instance);
  41. }
  42. // some sensors use zero offsets
  43. void set_use_zero_offset(void) {
  44. frontend.state[instance].use_zero_offset = true;
  45. }
  46. // set to no zero cal, which makes sense for some sensors
  47. void set_skip_cal(void) {
  48. frontend.param[instance].skip_cal.set(1);
  49. }
  50. // set zero offset
  51. void set_offset(float ofs) {
  52. frontend.param[instance].offset.set(ofs);
  53. }
  54. private:
  55. AP_Airspeed &frontend;
  56. uint8_t instance;
  57. };