APM:Libraries
AP_RangeFinder_Bebop.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 #include <AP_HAL/AP_HAL.h>
16 #include <utility>
17 
18 #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
19  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \
20  defined(HAVE_LIBIIO)
21 
22 #include <stdlib.h>
23 #include <unistd.h>
24 #include <stdio.h>
25 #include <fcntl.h>
26 #include <string.h>
27 #include <sys/mman.h>
28 #include <linux/types.h>
29 #include <errno.h>
30 #include <sys/ioctl.h>
31 #include <float.h>
32 #include <math.h>
33 #include <time.h>
34 #include <iio.h>
35 #include "AP_RangeFinder_Bebop.h"
36 #include <AP_HAL_Linux/Thread.h>
37 #include <AP_HAL_Linux/GPIO.h>
38 
39 /*
40  * this mode is used at low altitude
41  * send 4 wave patterns
42  * gpio in low mode
43  */
44 #define RNFD_BEBOP_DEFAULT_MODE 1
45 
46 /*
47  * the number of p7s in the iio buffer
48  */
49 #define RNFD_BEBOP_P7_COUNT 8192
50 
51 extern const AP_HAL::HAL& hal;
52 
53 static const uint16_t waveform_mode0[14] = {
54  4000, 3800, 3600, 3400, 3200, 3000, 2800,
55  2600, 2400, 2200, 2000, 1800, 1600, 1400,
56 };
57 
58 static const uint16_t waveform_mode1[32] = {
59  4190, 4158, 4095, 4095, 4095, 4095, 4095, 4095, 4095,
60  4095, 4090, 4058, 3943, 3924, 3841, 3679, 3588, 3403,
61  3201, 3020, 2816, 2636, 2448, 2227, 2111, 1955, 1819,
62  1675, 1540, 1492, 1374, 1292
63 };
64 
66  AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_ULTRASOUND),
67  _thread(new Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void)))
68 {
69  _init();
71  _filtered_capture_size = _adc.buffer_size / _filter_average;
72  _filtered_capture = (unsigned int*) calloc(1, sizeof(_filtered_capture[0]) *
73  _filtered_capture_size);
74  _mode = RNFD_BEBOP_DEFAULT_MODE;
75  /* SPI and IIO can not be initialized just yet */
76  memset(_tx[0], 0xF0, 16);
77  memset(_tx[1], 0xF0, 4);
78  memset(_purge, 0xFF, RNFD_BEBOP_NB_PULSES_PURGE);
79  _tx_buf = _tx[_mode];
80 }
81 
83 {
84  iio_buffer_destroy(_adc.buffer);
85  _adc.buffer = nullptr;
86  iio_context_destroy(_iio);
87  _iio = nullptr;
88 }
89 
91 {
92  return true;
93 }
94 
95 unsigned short AP_RangeFinder_Bebop::get_threshold_at(int i_capture)
96 {
97  uint16_t threshold_value = 0;
98 
99  /*
100  * We define several kinds of thresholds signals ; for an echo to be
101  * recorded, its maximum amplitude has to be ABOVE that threshold.
102  * There is one kind of threshold per mode (mode 0 is "low" and mode 1 is
103  * "high")
104  * Basically they look like this :
105  *
106  * on this part
107  * of the capture
108  * amplitude we use
109  * ^ the waveform
110  * | <---------->
111  * 4195 +-----+
112  * |
113  * |
114  * |
115  * |
116  * 1200| +----------------+
117  * +-------------------------------------->
118  * + low high time
119  * limit limit
120  *
121  * */
122  switch (_mode) {
123  case 0:
124  if (i_capture < 139)
125  threshold_value = 4195;
126  else if (i_capture < 153)
127  threshold_value = waveform_mode0[i_capture - 139];
128  else
129  threshold_value = 1200;
130  break;
131 
132  case 1:
133  if (i_capture < 73)
134  threshold_value = 4195;
135  else if (i_capture < 105)
136  threshold_value = waveform_mode1[i_capture - 73];
137  else if (i_capture < 617)
138  threshold_value = 1200;
139  else
140  threshold_value = 4195;
141  break;
142 
143  default:
144  break;
145  }
146 
147  return threshold_value;
148 }
149 
151 {
152 
153  int i_filter = 0; /* index in the filtered buffer */
154  int i_capture = 0; /* index in the capture buffer : starts incrementing when
155  the captured data first exceeds
156  RNFD_BEBOP_THRESHOLD_ECHO_INIT */
157  unsigned int filtered_value = 0;
158  bool first_echo = false;
159  unsigned char *data;
160  unsigned char *start;
161  unsigned char *end;
162  ptrdiff_t step;
163 
164  step = iio_buffer_step(_adc.buffer);
165  end = (unsigned char *) iio_buffer_end(_adc.buffer);
166  start = (unsigned char *) iio_buffer_first(_adc.buffer, _adc.channel);
167 
168  for (data = start; data < end; data += step) {
169  unsigned int current_value = 0;
170  iio_channel_convert(_adc.channel, &current_value, data);
171 
172  /* We keep on advancing in the captured buffer without registering the
173  * filtered data until the signal first exceeds a given value */
174  if (!first_echo && current_value < threshold_echo_init)
175  continue;
176  else
177  first_echo = true;
178 
179  filtered_value += current_value;
180  if (i_capture % _filter_average == 0) {
181  _filtered_capture[i_filter] = filtered_value / _filter_average;
182  filtered_value = 0;
183  i_filter++;
184  }
185  i_capture++;
186  }
187  return 0;
188 }
189 
191 {
192  int i_echo = 0; /* index in echo array */
193 
194  for (int i_capture = 1; i_capture <
195  (int)_filtered_capture_size - 1; i_capture++) {
196  if (_filtered_capture[i_capture] >= get_threshold_at(i_capture)) {
197  unsigned short curr = _filtered_capture[i_capture];
198  unsigned short prev = _filtered_capture[i_capture - 1];
199  unsigned short next = _filtered_capture[i_capture + 1];
200 
201  if (curr >= prev && (curr > next || prev <
202  get_threshold_at(i_capture - 1))) {
203  _echoes[i_echo].max_index = i_capture;
204  i_echo++;
205  if (i_echo >= RNFD_BEBOP_MAX_ECHOES)
206  break;
207  }
208  }
209  }
210  _nb_echoes = i_echo;
211  return 0;
212 }
213 
215 {
216  unsigned short max = 0;
217  int max_idx = -1;
218 
219  for (int i_echo = 0; i_echo < _nb_echoes ; i_echo++) {
220  unsigned short curr = _filtered_capture[_echoes[i_echo].max_index];
221  if (curr > max) {
222  max = curr;
223  max_idx = i_echo;
224  }
225  }
226 
227  if (max_idx >= 0)
228  return _echoes[max_idx].max_index;
229  else
230  return -1;
231 }
232 
234 {
235  int max_index;
236 
237  while(1) {
238  _launch();
239 
240  _capture();
241 
242  if (_apply_averaging_filter() < 0) {
243  hal.console->printf(
244  "AR_RangeFinder_Bebop: could not apply averaging filter");
245  }
246 
247  if (_search_local_maxima() < 0) {
248  hal.console->printf("Did not find any local maximum");
249  }
250 
251  max_index = _search_maximum_with_max_amplitude();
252  if (max_index >= 0) {
253  _altitude = (float)(max_index * RNFD_BEBOP_SOUND_SPEED) /
254  (2 * (RNFD_BEBOP_DEFAULT_ADC_FREQ / _filter_average));
255  }
256  _mode = _update_mode(_altitude);
257  }
258 }
259 
261 {
262  static bool first_call = true;
263 
264  if (first_call) {
265  _thread->start("RangeFinder_Bebop", SCHED_FIFO, 11);
266  first_call = false;
267  }
268 
269  state.distance_cm = (uint16_t) (_altitude * 100);
270  update_status();
271 }
272 
273 /*
274  * purge is used when changing mode
275  */
277 {
278  iio_device_attr_write(_adc.device, "buffer/enable", "1");
279  _spi->transfer(_purge, RNFD_BEBOP_NB_PULSES_PURGE, nullptr, 0);
280  return 0;
281 }
282 
284 {
285  switch (value) {
286  case 1: // high voltage
287  _gpio->write(LINUX_GPIO_ULTRASOUND_VOLTAGE, 1);
288  break;
289  case 0: // low voltage
290  _gpio->write(LINUX_GPIO_ULTRASOUND_VOLTAGE, 0);
291  break;
292  default:
293  hal.console->printf("bad gpio value (%d)", value);
294  break;
295  }
296 }
297 
298 /*
299  * reconfigure the pulse that will be sent over spi
300  * first send a purge then configure the new pulse
301  */
303 {
304  /* configure the output buffer for a purge */
305  /* perform a purge */
306  if (_launch_purge() < 0)
307  hal.console->printf("purge could not send data overspi");
308  if (_capture() < 0)
309  hal.console->printf("purge could not capture data");
310 
311  _tx_buf = _tx[_mode];
312  switch (_mode) {
313  case 1: /* low voltage */
314  _configure_gpio(0);
315  break;
316  case 0: /* high voltage */
317  _configure_gpio(1);
318  break;
319  default:
320  hal.console->printf("WARNING, invalid value to configure gpio\n");
321  break;
322  }
323 }
324 
325 /*
326  * First configuration of the the pulse that will be send over spi
327  */
329 {
330  _spi->set_speed(AP_HAL::Device::SPEED_HIGH);
331  _configure_gpio(0);
332  return 0;
333 }
334 
335 /*
336  * Configure the adc to get the samples
337  */
339 {
340  const char *adcname = "p7mu-adc_2";
341  const char *adcchannel = "voltage2";
342  /* configure adc interface using libiio */
343  _iio = iio_create_local_context();
344  if (!_iio)
345  return -1;
346  _adc.device = iio_context_find_device(_iio, adcname);
347 
348  if (!_adc.device) {
349  hal.console->printf("Unable to find %s", adcname);
350  goto error_destroy_context;
351  }
352  _adc.channel = iio_device_find_channel(_adc.device, adcchannel,
353  false);
354  if (!_adc.channel) {
355  hal.console->printf("Fail to init adc channel %s", adcchannel);
356  goto error_destroy_context;
357  }
358 
359  iio_channel_enable(_adc.channel);
360 
362  _adc.threshold_time_rejection = 2.0 / RNFD_BEBOP_SOUND_SPEED *
363  _adc.freq;
364 
365  /* Create input buffer */
366  _adc.buffer_size = RNFD_BEBOP_P7_COUNT;
367  if (iio_device_set_kernel_buffers_count(_adc.device, 1)) {
368  hal.console->printf("cannot set buffer count");
369  goto error_destroy_context;
370  }
371  _adc.buffer = iio_device_create_buffer(_adc.device,
372  _adc.buffer_size, false);
373  if (!_adc.buffer) {
374  hal.console->printf("Fail to create buffer : %s", strerror(errno));
375  goto error_destroy_context;
376  }
377 
378  return 0;
379 
380 error_destroy_context:
381  iio_buffer_destroy(_adc.buffer);
382  _adc.buffer = nullptr;
383  iio_context_destroy(_iio);
384  _iio = nullptr;
385  return -1;
386 }
387 
389 {
390  _spi = std::move(hal.spi->get_device("bebop"));
391 
392  _gpio = AP_HAL::get_HAL().gpio;
393  if (_gpio == nullptr) {
394  AP_HAL::panic("Could not find GPIO device for Bebop ultrasound");
395  }
396 
397  if (_configure_capture() < 0) {
398  return;
399  }
400 
401  _configure_wave();
402 
403  return;
404 }
405 
406 /*
407  * enable the capture buffer
408  * send a pulse over spi
409  */
411 {
412  iio_device_attr_write(_adc.device, "buffer/enable", "1");
413  _spi->transfer(_tx_buf, RNFD_BEBOP_NB_PULSES_MAX, nullptr, 0);
414  return 0;
415 }
416 
417 /*
418  * read the iio buffer
419  * iio_buffer_refill is blocking by default, so this function is also
420  * blocking until samples are available
421  * disable the capture buffer
422  */
424 {
425  int ret;
426 
427  ret = iio_buffer_refill(_adc.buffer);
428  iio_device_attr_write(_adc.device, "buffer/enable", "0");
429  return ret;
430 }
431 
432 int AP_RangeFinder_Bebop::_update_mode(float altitude)
433 {
434  switch (_mode) {
435  case 0:
436  if (altitude < RNFD_BEBOP_TRANSITION_HIGH_TO_LOW
437  && !is_zero(altitude)) {
438  if (_hysteresis_counter > RNFD_BEBOP_TRANSITION_COUNT) {
439  _mode = 1;
440  _hysteresis_counter = 0;
441  _reconfigure_wave();
442  } else {
443  _hysteresis_counter++;
444  }
445  } else {
446  _hysteresis_counter = 0;
447  }
448  break;
449 
450  default:
451  case 1:
452  if (altitude > RNFD_BEBOP_TRANSITION_LOW_TO_HIGH
453  || is_zero(altitude)) {
454  if (_hysteresis_counter > RNFD_BEBOP_TRANSITION_COUNT) {
455  _mode = 0;
456  _hysteresis_counter = 0;
457  _reconfigure_wave();
458  } else {
459  _hysteresis_counter++;
460  }
461  } else {
462  _hysteresis_counter = 0;
463  }
464  break;
465  }
466  return _mode;
467 }
468 #endif
int _update_mode(float altitude)
#define RNFD_BEBOP_TRANSITION_LOW_TO_HIGH
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define RNFD_BEBOP_MAX_ECHOES
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
static int max(int a, int b)
Definition: compat.h:35
#define RNFD_BEBOP_DEFAULT_FREQ
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define RNFD_BEBOP_FILTER_POWER
unsigned short get_threshold_at(int i_capture)
void _configure_gpio(int value)
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
static bool detect()
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state)
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
#define RNFD_BEBOP_NB_PULSES_MAX
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define RNFD_BEBOP_NB_PULSES_PURGE
int _search_local_maxima(void)
#define RNFD_BEBOP_TRANSITION_COUNT
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
const HAL & get_HAL()
#define RNFD_BEBOP_DEFAULT_ADC_FREQ
#define RNFD_BEBOP_TRANSITION_HIGH_TO_LOW
AP_HAL::GPIO * gpio
Definition: HAL.h:111
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
float value
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
RangeFinder::RangeFinder_State & state
#define RNFD_BEBOP_SOUND_SPEED
int _apply_averaging_filter(void)
int _search_maximum_with_max_amplitude(void)