APM:Libraries
AP_RPM.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_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
21 
22 // Maximum number of RPM measurement instances available on this platform
23 #define RPM_MAX_INSTANCES 2
24 
25 class AP_RPM_Backend;
26 
27 class AP_RPM
28 {
29  friend class AP_RPM_Backend;
30 
31 public:
32  AP_RPM();
33 
34  /* Do not allow copies */
35  AP_RPM(const AP_RPM &other) = delete;
36  AP_RPM &operator=(const AP_RPM&) = delete;
37 
38  // RPM driver types
39  enum RPM_Type {
43  };
44 
45  // The RPM_State structure is filled in by the backend driver
46  struct RPM_State {
47  uint8_t instance; // the instance number of this RPM
48  float rate_rpm; // measured rate in revs per minute
49  uint32_t last_reading_ms; // time of last reading
50  float signal_quality; // synthetic quality metric
51  };
52 
53  // parameters for each instance
60 
61  static const struct AP_Param::GroupInfo var_info[];
62 
63  // Return the number of rpm sensor instances
64  uint8_t num_sensors(void) const {
65  return num_instances;
66  }
67 
68  // detect and initialise any available rpm sensors
69  void init(void);
70 
71  // update state of all rpm sensors. Should be called from main loop
72  void update(void);
73 
74  /*
75  return RPM for a sensor. Return -1 if not healthy
76  */
77  float get_rpm(uint8_t instance) const {
78  if (!healthy(instance)) {
79  return -1;
80  }
81  return state[instance].rate_rpm;
82  }
83 
84  /*
85  return signal quality for a sensor.
86  */
87  float get_signal_quality(uint8_t instance) const {
89  }
90 
91  bool healthy(uint8_t instance) const;
92 
93  bool enabled(uint8_t instance) const;
94 
95 private:
98  uint8_t num_instances:2;
99 
100  void detect_instance(uint8_t instance);
101  void update_instance(uint8_t instance);
102 };
uint8_t num_sensors(void) const
Definition: AP_RPM.h:64
uint8_t num_instances
Definition: AP_RPM.h:98
AP_Float _minimum[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:58
void update(void)
Definition: AP_RPM.cpp:148
bool enabled(uint8_t instance) const
Definition: AP_RPM.cpp:181
float get_rpm(uint8_t instance) const
Definition: AP_RPM.h:77
float signal_quality
Definition: AP_RPM.h:50
void init(void)
Definition: AP_RPM.cpp:106
AP_RPM()
Definition: AP_RPM.cpp:93
uint32_t last_reading_ms
Definition: AP_RPM.h:49
RPM_State state[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:96
AP_RPM & operator=(const AP_RPM &)=delete
RPM_Type
Definition: AP_RPM.h:39
uint8_t instance
Definition: AP_RPM.h:47
A system for managing and storing variables that are of general interest to the system.
AP_Int8 _type[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:54
bool healthy(uint8_t instance) const
Definition: AP_RPM.cpp:164
#define RPM_MAX_INSTANCES
Definition: AP_RPM.h:23
AP_Int8 _pin[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:55
Definition: AP_RPM.h:27
AP_Float _quality_min[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:59
Common definitions and utility routines for the ArduPilot libraries.
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_RPM.h:61
void update_instance(uint8_t instance)
AP_Float _maximum[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:57
AP_RPM_Backend * drivers[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:97
AP_Float _scaling[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:56
float rate_rpm
Definition: AP_RPM.h:48
void detect_instance(uint8_t instance)
float get_signal_quality(uint8_t instance) const
Definition: AP_RPM.h:87