RPM_Backend.h 1.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445
  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. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include "AP_RPM.h"
  17. class AP_RPM_Backend
  18. {
  19. public:
  20. // constructor. This incorporates initialisation as well.
  21. AP_RPM_Backend(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state);
  22. // we declare a virtual destructor so that RPM drivers can
  23. // override with a custom destructor if need be
  24. virtual ~AP_RPM_Backend(void) {}
  25. // update the state structure. All backends must implement this.
  26. virtual void update() = 0;
  27. int8_t get_pin(void) const {
  28. if (state.instance >= RPM_MAX_INSTANCES) {
  29. return -1;
  30. }
  31. return ap_rpm._pin[state.instance].get();
  32. }
  33. protected:
  34. AP_RPM &ap_rpm;
  35. AP_RPM::RPM_State &state;
  36. };