APM:Libraries
AP_RPM.cpp
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 
16 #include "AP_RPM.h"
17 #include "RPM_PX4_PWM.h"
18 #include "RPM_Pin.h"
19 #include "RPM_SITL.h"
20 
21 extern const AP_HAL::HAL& hal;
22 
23 // table of user settable parameters
25  // @Param: _TYPE
26  // @DisplayName: RPM type
27  // @Description: What type of RPM sensor is connected
28  // @Values: 0:None,1:PX4-PWM,2:AUXPIN
29  // @User: Standard
30  AP_GROUPINFO("_TYPE", 0, AP_RPM, _type[0], 0),
31 
32  // @Param: _SCALING
33  // @DisplayName: RPM scaling
34  // @Description: Scaling factor between sensor reading and RPM.
35  // @Increment: 0.001
36  // @User: Standard
37  AP_GROUPINFO("_SCALING", 1, AP_RPM, _scaling[0], 1.0f),
38 
39  // @Param: _MAX
40  // @DisplayName: Maximum RPM
41  // @Description: Maximum RPM to report
42  // @Increment: 1
43  // @User: Standard
44  AP_GROUPINFO("_MAX", 2, AP_RPM, _maximum[0], 100000),
45 
46  // @Param: _MIN
47  // @DisplayName: Minimum RPM
48  // @Description: Minimum RPM to report
49  // @Increment: 1
50  // @User: Standard
51  AP_GROUPINFO("_MIN", 3, AP_RPM, _minimum[0], 10),
52 
53  // @Param: _MIN_QUAL
54  // @DisplayName: Minimum Quality
55  // @Description: Minimum data quality to be used
56  // @Increment: 0.1
57  // @User: Advanced
58  AP_GROUPINFO("_MIN_QUAL", 4, AP_RPM, _quality_min[0], 0.5),
59 
60  // @Param: _PIN
61  // @DisplayName: Input pin number
62  // @Description: Which pin to use
63  // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
64  // @User: Standard
65  AP_GROUPINFO("_PIN", 5, AP_RPM, _pin[0], 54),
66 
67 #if RPM_MAX_INSTANCES > 1
68  // @Param: 2_TYPE
69  // @DisplayName: Second RPM type
70  // @Description: What type of RPM sensor is connected
71  // @Values: 0:None,1:PX4-PWM,2:AUXPIN
72  // @User: Advanced
73  AP_GROUPINFO("2_TYPE", 10, AP_RPM, _type[1], 0),
74 
75  // @Param: 2_SCALING
76  // @DisplayName: RPM scaling
77  // @Description: Scaling factor between sensor reading and RPM.
78  // @Increment: 0.001
79  // @User: Advanced
80  AP_GROUPINFO("2_SCALING", 11, AP_RPM, _scaling[1], 1.0f),
81 #endif
82 
83  // @Param: 2_PIN
84  // @DisplayName: RPM2 input pin number
85  // @Description: Which pin to use
86  // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
87  // @User: Standard
88  AP_GROUPINFO("2_PIN", 12, AP_RPM, _pin[1], -1),
89 
91 };
92 
94  num_instances(0)
95 {
97 
98  // init state and drivers
99  memset(state,0,sizeof(state));
100  memset(drivers,0,sizeof(drivers));
101 }
102 
103 /*
104  initialise the AP_RPM class.
105  */
106 void AP_RPM::init(void)
107 {
108  if (num_instances != 0) {
109  // init called a 2nd time?
110  return;
111  }
112  for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
113 #if (CONFIG_HAL_BOARD == HAL_BOARD_PX4) || ((CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN) && (!defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) && !defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)))
114  {
115  uint8_t type = _type[num_instances];
116  uint8_t instance = num_instances;
117 
118  if (type == RPM_TYPE_PX4_PWM) {
119  state[instance].instance = instance;
120  drivers[instance] = new AP_RPM_PX4_PWM(*this, instance, state[instance]);
121  }
122  }
123 #endif
124  {
125  uint8_t type = _type[num_instances];
126  uint8_t instance = num_instances;
127  if (type == RPM_TYPE_PIN) {
128  state[instance].instance = instance;
129  drivers[instance] = new AP_RPM_Pin(*this, instance, state[instance]);
130  }
131  }
132 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
133  uint8_t instance = num_instances;
134  state[instance].instance = instance;
135  drivers[instance] = new AP_RPM_SITL(*this, instance, state[instance]);
136 #endif
137  if (drivers[i] != nullptr) {
138  // we loaded a driver for this instance, so it must be
139  // present (although it may not be healthy)
140  num_instances = i+1;
141  }
142  }
143 }
144 
145 /*
146  update RPM state for all instances. This should be called by main loop
147  */
148 void AP_RPM::update(void)
149 {
150  for (uint8_t i=0; i<num_instances; i++) {
151  if (drivers[i] != nullptr) {
152  if (_type[i] == RPM_TYPE_NONE) {
153  // allow user to disable a RPM sensor at runtime
154  continue;
155  }
156  drivers[i]->update();
157  }
158  }
159 }
160 
161 /*
162  check if an instance is healthy
163  */
164 bool AP_RPM::healthy(uint8_t instance) const
165 {
166  if (instance >= num_instances) {
167  return false;
168  }
169 
170  // check that data quality is above minimum required
171  if (state[instance].signal_quality < _quality_min[0]) {
172  return false;
173  }
174 
175  return true;
176 }
177 
178 /*
179  check if an instance is activated
180  */
181 bool AP_RPM::enabled(uint8_t instance) const
182 {
183  if (instance >= num_instances) {
184  return false;
185  }
186  // if no sensor type is selected, the sensor is not activated.
187  if (_type[instance] == RPM_TYPE_NONE) {
188  return false;
189  }
190  return true;
191 }
uint8_t num_instances
Definition: AP_RPM.h:98
void update(void)
Definition: AP_RPM.cpp:148
bool enabled(uint8_t instance) const
Definition: AP_RPM.cpp:181
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void init(void)
Definition: AP_RPM.cpp:106
AP_RPM()
Definition: AP_RPM.cpp:93
RPM_State state[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:96
uint8_t instance
Definition: AP_RPM.h:47
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
#define f(i)
Definition: AP_RPM.h:27
AP_Float _quality_min[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:59
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_RPM.h:61
virtual void update()=0
AP_RPM_Backend * drivers[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:97
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214