APM:Libraries
RPM_PX4_PWM.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 
18 #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)))
20 #include "RPM_PX4_PWM.h"
21 
22 #include <sys/types.h>
23 #include <sys/stat.h>
24 #include <fcntl.h>
25 #include <unistd.h>
26 
27 #include <drivers/drv_pwm_input.h>
28 #include <drivers/drv_hrt.h>
29 #include <drivers/drv_sensor.h>
30 #include <uORB/topics/pwm_input.h>
31 #include <stdio.h>
32 #include <errno.h>
33 #include <cmath>
34 
35 #define PWM_LOGGING 0
36 
37 extern const AP_HAL::HAL& hal;
38 
39 extern "C" {
40  int pwm_input_main(int, char **);
41 };
42 
43 /*
44  open the sensor in constructor
45 */
46 AP_RPM_PX4_PWM::AP_RPM_PX4_PWM(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) :
47  AP_RPM_Backend(_ap_rpm, instance, _state)
48 {
49 #if HAL_PX4_HAVE_PWM_INPUT
50  if (AP_BoardConfig::px4_start_driver(pwm_input_main, "pwm_input", "start")) {
51  hal.console->printf("started pwm_input driver\n");
52  }
53 #endif
54  _fd = open(PWMIN0_DEVICE_PATH, O_RDONLY);
55  if (_fd == -1) {
56  hal.console->printf("Unable to open %s\n", PWMIN0_DEVICE_PATH);
57  return;
58  }
59 
60  // keep a queue of 5 samples to reduce noise by averaging
61  if (ioctl(_fd, SENSORIOCSQUEUEDEPTH, 5) != 0) {
62  hal.console->printf("Failed to setup RPM queue\n");
63  close(_fd);
64  _fd = -1;
65  return;
66  }
67 
68  _resolution_usec = PWMIN_MINRPM_TO_RESOLUTION(((uint32_t)(ap_rpm._minimum[state.instance]+0.5f)));
69  ioctl(_fd, PWMINIOSRESOLUTION, _resolution_usec);
70 
71 #if PWM_LOGGING
72  _logfd = open("/fs/microsd/pwm.log", O_WRONLY|O_CREAT|O_TRUNC, 0644);
73 #endif
74 }
75 
76 /*
77  close the file descriptor
78 */
80 {
81  if (_fd != -1) {
82  close(_fd);
83  _fd = -1;
84  }
85 }
86 
88 {
89  if (_fd == -1) {
90  return;
91  }
92 
93  uint32_t newres = PWMIN_MINRPM_TO_RESOLUTION(((uint32_t)(ap_rpm._minimum[state.instance]+0.5f)));
94  if (newres != _resolution_usec) {
95  ioctl(_fd, PWMINIOSRESOLUTION, newres);
96  _resolution_usec = newres;
97  }
98 
99  struct pwm_input_s pwm;
100  uint16_t count = 0;
101  const float scaling = ap_rpm._scaling[state.instance];
102  float maximum = ap_rpm._maximum[state.instance];
103  float minimum = ap_rpm._minimum[state.instance];
104  float quality = 0;
105 
106  while (::read(_fd, &pwm, sizeof(pwm)) == sizeof(pwm)) {
107  // the px4 pwm_input driver reports the period in microseconds
108  if (pwm.period == 0) {
109  continue;
110  }
111  float rpm = scaling * (1.0e6f * 60) / pwm.period;
112  float filter_value = signal_quality_filter.get();
114  if ((maximum <= 0 || rpm <= maximum) && (rpm >= minimum)) {
115  if (is_zero(filter_value)){
116  quality = 0;
117  } else {
118  quality = 1 - constrain_float((fabsf(rpm-filter_value))/filter_value, 0.0, 1.0);
119  quality = powf(quality, 2.0);
120  }
121  count++;
122  } else {
123  quality = 0;
124  }
125 
126 #if PWM_LOGGING
127  if (_logfd != -1) {
128  dprintf(_logfd, "%u %u %u\n",
129  (unsigned)pwm.timestamp/1000,
130  (unsigned)pwm.period,
131  (unsigned)pwm.pulse_width);
132  }
133 #endif
134 
135  state.signal_quality = (0.1 * quality) + (0.9 * state.signal_quality); // simple LPF
136  }
137 
138  if (count != 0) {
140  }
141 
142  // assume we get readings at at least 1Hz, otherwise reset quality to zero
143  if (AP_HAL::millis() - state.last_reading_ms > 1000) {
144  state.signal_quality = 0;
145  }
146 }
147 
148 #endif // CONFIG_HAL_BOARD
float scaling
Definition: AnalogIn.cpp:40
AP_Float _minimum[RPM_MAX_INSTANCES]
Definition: AP_RPM.h:58
AP_RPM & ap_rpm
Definition: RPM_Backend.h:43
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
float signal_quality
Definition: AP_RPM.h:50
ModeFilterFloat_Size5 signal_quality_filter
Definition: RPM_PX4_PWM.h:40
AP_RPM_PX4_PWM(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state)
Definition: RPM_PX4_PWM.cpp:46
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
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
AP_RPM::RPM_State & state
Definition: RPM_Backend.h:44
uint32_t _resolution_usec
Definition: RPM_PX4_PWM.h:38
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments)
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
Definition: AP_RPM.h:27
void update(void)
Definition: RPM_PX4_PWM.cpp:87
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual T get() const
Definition: ModeFilter.h:36
int pwm_input_main(int, char **)
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
~AP_RPM_PX4_PWM(void)
Definition: RPM_PX4_PWM.cpp:79