APM:Libraries
AP_RangeFinder_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
20 #include "AP_RangeFinder_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 extern const AP_HAL::HAL& hal;
36 
37 extern "C" {
38  int pwm_input_main(int, char **);
39 };
40 
41 /*
42  The constructor also initialises the rangefinder. Note that this
43  constructor is not called until detect() returns true, so we
44  already know that we should setup the rangefinder
45 */
46 AP_RangeFinder_PX4_PWM::AP_RangeFinder_PX4_PWM(RangeFinder::RangeFinder_State &_state, AP_Int16 &powersave_range, float &_estimated_terrain_height) :
47  AP_RangeFinder_Backend(_state),
48  _powersave_range(powersave_range),
49  estimated_terrain_height(_estimated_terrain_height)
50 {
51  _fd = open(PWMIN0_DEVICE_PATH, O_RDONLY);
52  if (_fd == -1) {
53  hal.console->printf("Unable to open PX4 PWM rangefinder\n");
55  return;
56  }
57 
58  // keep a queue of 20 samples
59  if (ioctl(_fd, SENSORIOCSQUEUEDEPTH, 20) != 0) {
60  hal.console->printf("Failed to setup range finder queue\n");
62  return;
63  }
64 
65  // initialise to connected but no data
67 }
68 
69 /*
70  close the file descriptor
71 */
73 {
74  if (_fd != -1) {
75  close(_fd);
76  }
78 }
79 
80 /*
81  see if the PX4 driver is available
82 */
84 {
85 #if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
86  !defined(CONFIG_ARCH_BOARD_AEROFC_V1)
87  if (AP_BoardConfig::px4_start_driver(pwm_input_main, "pwm_input", "start")) {
88  hal.console->printf("started pwm_input driver\n");
89  }
90 #endif
91  int fd = open(PWMIN0_DEVICE_PATH, O_RDONLY);
92  if (fd == -1) {
93  return false;
94  }
95  close(fd);
96  return true;
97 }
98 
100 {
101  if (_fd == -1) {
103  return;
104  }
105 
106  struct pwm_input_s pwm;
107  float sum_cm = 0;
108  uint16_t count = 0;
109  const float scaling = state.scaling;
110  uint32_t now = AP_HAL::millis();
111 
112  while (::read(_fd, &pwm, sizeof(pwm)) == sizeof(pwm)) {
113  // report the voltage as the pulse width, so we get the raw
114  // pulse widths in the log
115  state.voltage_mv = pwm.pulse_width;
116 
117  _last_pulse_time_ms = now;
118 
119  // setup for scaling in meters per millisecond
120  float _distance_cm = pwm.pulse_width * 0.1f * scaling + state.offset;
121 
122  float distance_delta_cm = fabsf(_distance_cm - _last_sample_distance_cm);
123  _last_sample_distance_cm = _distance_cm;
124 
125  if (distance_delta_cm > 100) {
126  // varying by more than 1m in a single sample, which means
127  // between 50 and 100m/s vertically - discard
128  _good_sample_count = 0;
129  continue;
130  }
131 
132  if (_good_sample_count > 1) {
133  count++;
134  sum_cm += _distance_cm;
135  _last_timestamp = pwm.timestamp;
136  } else {
138  }
139  }
140 
141  // if we haven't received a pulse for 1 second then we may need to
142  // reset the timer
143  int8_t stop_pin = state.stop_pin;
144  uint16_t settle_time_ms = (uint16_t)state.settle_time_ms;
145 
146  if (stop_pin != -1 && out_of_range()) {
147  // we are above the power saving range. Disable the sensor
148  hal.gpio->pinMode(stop_pin, HAL_GPIO_OUTPUT);
149  hal.gpio->write(stop_pin, false);
151  state.distance_cm = 0;
152  state.voltage_mv = 0;
153  return;
154  }
155 
156  // if we have not taken a reading in the last 0.2s set status to No Data
157  if (AP_HAL::micros64() - _last_timestamp >= 200000) {
159  }
160 
161  /* if we haven't seen any pulses for 0.5s then the sensor is
162  probably dead. Try resetting it. Tests show the sensor takes
163  about 0.2s to boot, so 500ms offers some safety margin
164  */
165  if (now - _last_pulse_time_ms > 500U && _disable_time_ms == 0) {
166  ioctl(_fd, SENSORIOCRESET, 0);
167  _last_pulse_time_ms = now;
168 
169  // if a stop pin is configured then disable the sensor for the
170  // settle time
171  if (stop_pin != -1) {
172  hal.gpio->pinMode(stop_pin, HAL_GPIO_OUTPUT);
173  hal.gpio->write(stop_pin, false);
174  _disable_time_ms = now;
175  }
176  }
177 
178  /* the user can configure a settle time. This controls how
179  long the sensor is disabled for using the stop pin when it is
180  reset. This is used both to make sure the sensor is properly
181  reset, and also to allow for power management by running a low
182  duty cycle when it has no signal
183  */
184  if (stop_pin != -1 && _disable_time_ms != 0 &&
185  (now - _disable_time_ms > settle_time_ms)) {
186  hal.gpio->write(stop_pin, true);
187  _disable_time_ms = 0;
188  _last_pulse_time_ms = now;
189  }
190 
191  if (count != 0) {
192  state.distance_cm = sum_cm / count;
193 
194  // update range_valid state based on distance measured
195  update_status();
196  }
197 }
198 
199 #endif // CONFIG_HAL_BOARD
float scaling
Definition: AnalogIn.cpp:40
int pwm_input_main(int, char **)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
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
virtual void write(uint8_t pin, uint8_t value)=0
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
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
uint64_t micros64()
Definition: system.cpp:162
virtual void pinMode(uint8_t pin, uint8_t output)=0
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
AP_HAL::GPIO * gpio
Definition: HAL.h:111
AP_RangeFinder_PX4_PWM(RangeFinder::RangeFinder_State &_state, AP_Int16 &powersave_range, float &_estimated_terrain_height)
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state