APM:Libraries
RPM_Backend.h
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 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include "AP_RPM.h"
20 
22 {
23 public:
24  // constructor. This incorporates initialisation as well.
25  AP_RPM_Backend(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state);
26 
27  // we declare a virtual destructor so that RPM drivers can
28  // override with a custom destructor if need be
29  virtual ~AP_RPM_Backend(void) {}
30 
31  // update the state structure. All backends must implement this.
32  virtual void update() = 0;
33 
34  int8_t get_pin(void) const {
35  if (state.instance > 1) {
36  return -1;
37  }
38  return ap_rpm._pin[state.instance].get();
39  }
40 
41 protected:
42 
45 };
AP_RPM & ap_rpm
Definition: RPM_Backend.h:43
virtual ~AP_RPM_Backend(void)
Definition: RPM_Backend.h:29
uint8_t instance
Definition: AP_RPM.h:47
AP_RPM::RPM_State & state
Definition: RPM_Backend.h:44
AP_Int8 _pin[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:55
Definition: AP_RPM.h:27
AP_RPM_Backend(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state)
Definition: RPM_Backend.cpp:24
Common definitions and utility routines for the ArduPilot libraries.
int8_t get_pin(void) const
Definition: RPM_Backend.h:34
virtual void update()=0