APM:Libraries
RPM_Pin.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_HAL/AP_HAL.h>
17 #include "RPM_Pin.h"
18 
19 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
21 #include <board_config.h>
22 #endif
23 
24 #include <stdio.h>
25 
26 extern const AP_HAL::HAL& hal;
28 
29 /*
30  open the sensor in constructor
31 */
32 AP_RPM_Pin::AP_RPM_Pin(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) :
33  AP_RPM_Backend(_ap_rpm, instance, _state)
34 {
35 }
36 
37 /*
38  handle interrupt on an instance
39  */
40 void AP_RPM_Pin::irq_handler(uint8_t instance)
41 {
42  uint32_t now = AP_HAL::micros();
43  uint32_t dt = now - irq_state[instance].last_pulse_us;
44  irq_state[instance].last_pulse_us = now;
45  // we don't accept pulses less than 100us. Using an irq for such
46  // high RPM is too inaccurate, and it is probably just bounce of
47  // the signal which we should ignore
48  if (dt > 100 && dt < 1000*1000) {
49  irq_state[instance].dt_sum += dt;
50  irq_state[instance].dt_count++;
51  }
52 }
53 
54 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
55 /*
56  interrupt handler for instance 0
57  */
58 int AP_RPM_Pin::irq_handler0(int irq, void *context)
59 {
60  irq_handler(0);
61  return 0;
62 }
63 
64 /*
65  interrupt handler for instance 1
66  */
67 int AP_RPM_Pin::irq_handler1(int irq, void *context)
68 {
69  irq_handler(1);
70  return 0;
71 }
72 #else // other HALs
73 /*
74  interrupt handler for instance 0
75  */
76 void AP_RPM_Pin::irq_handler0(void)
77 {
78  irq_handler(0);
79 }
80 
81 /*
82  interrupt handler for instance 1
83  */
84 void AP_RPM_Pin::irq_handler1(void)
85 {
86  irq_handler(1);
87 }
88 #endif
89 
91 {
92  if (last_pin != get_pin()) {
93  last_pin = get_pin();
94 
95 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
96  uint32_t gpio = 0;
97 
98 #ifdef GPIO_GPIO0_INPUT
99  switch (last_pin) {
100  case 50:
101  gpio = GPIO_GPIO0_INPUT;
102  break;
103  case 51:
104  gpio = GPIO_GPIO1_INPUT;
105  break;
106  case 52:
107  gpio = GPIO_GPIO2_INPUT;
108  break;
109  case 53:
110  gpio = GPIO_GPIO3_INPUT;
111  break;
112  case 54:
113  gpio = GPIO_GPIO4_INPUT;
114  break;
115  case 55:
116  gpio = GPIO_GPIO5_INPUT;
117  break;
118  }
119 #endif // GPIO_GPIO5_INPUT
120 
121  // uninstall old handler if installed
122  if (last_gpio != 0) {
123  stm32_gpiosetevent(last_gpio, false, false, false, nullptr);
124  }
127 
128  last_gpio = gpio;
129 
130  if (gpio == 0) {
131  return;
132  }
133 
134  // install interrupt handler on rising edge of pin. This works
135  // for either polarity of pulse, as all we want is the period
136  stm32_gpiosetevent(gpio, true, false, false,
138 #else // other HALs
141 #endif
142  }
143 
144  if (irq_state[state.instance].dt_count > 0) {
145  float dt_avg;
146 
147  // disable interrupts to prevent race with irq_handler
148  void *irqstate = hal.scheduler->disable_interrupts_save();
152  hal.scheduler->restore_interrupts(irqstate);
153 
154  const float scaling = ap_rpm._scaling[state.instance];
155  float maximum = ap_rpm._maximum[state.instance];
156  float minimum = ap_rpm._minimum[state.instance];
157  float quality = 0;
158  float rpm = scaling * (1.0e6 / dt_avg) * 60;
159  float filter_value = signal_quality_filter.get();
160 
162 
163  if ((maximum <= 0 || rpm <= maximum) && (rpm >= minimum)) {
164  if (is_zero(filter_value)){
165  quality = 0;
166  } else {
167  quality = 1 - constrain_float((fabsf(rpm-filter_value))/filter_value, 0.0, 1.0);
168  quality = powf(quality, 2.0);
169  }
171  } else {
172  quality = 0;
173  }
174  state.signal_quality = (0.1 * quality) + (0.9 * state.signal_quality);
175  }
176 
177  // assume we get readings at at least 1Hz, otherwise reset quality to zero
178  if (AP_HAL::millis() - state.last_reading_ms > 1000) {
179  state.signal_quality = 0;
180  state.rate_rpm = 0;
181  }
182 }
float scaling
Definition: AnalogIn.cpp:40
ModeFilterFloat_Size5 signal_quality_filter
Definition: RPM_Pin.h:42
AP_Float _minimum[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:58
AP_RPM & ap_rpm
Definition: RPM_Backend.h:43
AP_RPM_Pin(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state)
Definition: RPM_Pin.cpp:32
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
float signal_quality
Definition: AP_RPM.h:50
uint32_t dt_count
Definition: RPM_Pin.h:48
uint32_t last_gpio
Definition: RPM_Pin.h:44
uint32_t last_reading_ms
Definition: AP_RPM.h:49
virtual T apply(T sample)
Definition: ModeFilter.h:91
uint8_t instance
Definition: AP_RPM.h:47
static int irq_handler1(int irq, void *context)
Definition: RPM_Pin.cpp:67
static int irq_handler0(int irq, void *context)
Definition: RPM_Pin.cpp:58
virtual bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)=0
AP_RPM::RPM_State & state
Definition: RPM_Backend.h:44
#define RPM_MAX_INSTANCES
Definition: AP_RPM.h:23
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
uint32_t millis()
Definition: system.cpp:157
Definition: AP_RPM.h:27
static struct IrqState irq_state[RPM_MAX_INSTANCES]
Definition: RPM_Pin.h:50
#define HAL_GPIO_INTERRUPT_RISING
Definition: GPIO.h:13
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
int8_t get_pin(void) const
Definition: RPM_Backend.h:34
static void irq_handler(uint8_t instance)
Definition: RPM_Pin.cpp:40
AP_HAL::GPIO * gpio
Definition: HAL.h:111
uint8_t last_pin
Definition: RPM_Pin.h:43
virtual void restore_interrupts(void *)
Definition: Scheduler.h:84
uint32_t last_pulse_us
Definition: RPM_Pin.h:46
void update(void)
Definition: RPM_Pin.cpp:90
virtual T get() const
Definition: ModeFilter.h:36
AP_Float _maximum[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:57
AP_Float _scaling[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:56
float rate_rpm
Definition: AP_RPM.h:48
virtual void * disable_interrupts_save(void)
Definition: Scheduler.h:79
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint32_t dt_sum
Definition: RPM_Pin.h:47