18 #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ 19 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \ 28 #include <linux/types.h> 44 #define RNFD_BEBOP_DEFAULT_MODE 1 49 #define RNFD_BEBOP_P7_COUNT 8192 53 static const uint16_t waveform_mode0[14] = {
54 4000, 3800, 3600, 3400, 3200, 3000, 2800,
55 2600, 2400, 2200, 2000, 1800, 1600, 1400,
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
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;
76 memset(_tx[0], 0xF0, 16);
77 memset(_tx[1], 0xF0, 4);
84 iio_buffer_destroy(_adc.buffer);
85 _adc.buffer =
nullptr;
86 iio_context_destroy(_iio);
97 uint16_t threshold_value = 0;
125 threshold_value = 4195;
126 else if (i_capture < 153)
127 threshold_value = waveform_mode0[i_capture - 139];
129 threshold_value = 1200;
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;
140 threshold_value = 4195;
147 return threshold_value;
157 unsigned int filtered_value = 0;
158 bool first_echo =
false;
160 unsigned char *start;
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);
168 for (data = start; data <
end; data += step) {
169 unsigned int current_value = 0;
170 iio_channel_convert(_adc.channel, ¤t_value, data);
174 if (!first_echo && current_value < threshold_echo_init)
179 filtered_value += current_value;
180 if (i_capture % _filter_average == 0) {
181 _filtered_capture[i_filter] = filtered_value / _filter_average;
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];
201 if (curr >= prev && (curr > next || prev <
202 get_threshold_at(i_capture - 1))) {
203 _echoes[i_echo].max_index = i_capture;
216 unsigned short max = 0;
219 for (
int i_echo = 0; i_echo < _nb_echoes ; i_echo++) {
220 unsigned short curr = _filtered_capture[_echoes[i_echo].max_index];
228 return _echoes[max_idx].max_index;
242 if (_apply_averaging_filter() < 0) {
244 "AR_RangeFinder_Bebop: could not apply averaging filter");
247 if (_search_local_maxima() < 0) {
251 max_index = _search_maximum_with_max_amplitude();
252 if (max_index >= 0) {
256 _mode = _update_mode(_altitude);
262 static bool first_call =
true;
265 _thread->start(
"RangeFinder_Bebop", SCHED_FIFO, 11);
278 iio_device_attr_write(_adc.device,
"buffer/enable",
"1");
306 if (_launch_purge() < 0)
311 _tx_buf = _tx[_mode];
320 hal.
console->
printf(
"WARNING, invalid value to configure gpio\n");
340 const char *adcname =
"p7mu-adc_2";
341 const char *adcchannel =
"voltage2";
343 _iio = iio_create_local_context();
346 _adc.device = iio_context_find_device(_iio, adcname);
350 goto error_destroy_context;
352 _adc.channel = iio_device_find_channel(_adc.device, adcchannel,
355 hal.
console->
printf(
"Fail to init adc channel %s", adcchannel);
356 goto error_destroy_context;
359 iio_channel_enable(_adc.channel);
366 _adc.buffer_size = RNFD_BEBOP_P7_COUNT;
367 if (iio_device_set_kernel_buffers_count(_adc.device, 1)) {
369 goto error_destroy_context;
371 _adc.buffer = iio_device_create_buffer(_adc.device,
372 _adc.buffer_size,
false);
375 goto error_destroy_context;
380 error_destroy_context:
381 iio_buffer_destroy(_adc.buffer);
382 _adc.buffer =
nullptr;
383 iio_context_destroy(_iio);
393 if (_gpio ==
nullptr) {
394 AP_HAL::panic(
"Could not find GPIO device for Bebop ultrasound");
397 if (_configure_capture() < 0) {
412 iio_device_attr_write(_adc.device,
"buffer/enable",
"1");
427 ret = iio_buffer_refill(_adc.buffer);
428 iio_device_attr_write(_adc.device,
"buffer/enable",
"0");
440 _hysteresis_counter = 0;
443 _hysteresis_counter++;
446 _hysteresis_counter = 0;
456 _hysteresis_counter = 0;
459 _hysteresis_counter++;
462 _hysteresis_counter = 0;
int _update_mode(float altitude)
#define RNFD_BEBOP_TRANSITION_LOW_TO_HIGH
AP_HAL::UARTDriver * console
#define RNFD_BEBOP_MAX_ECHOES
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
static int max(int a, int b)
#define RNFD_BEBOP_DEFAULT_FREQ
#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)
~AP_RangeFinder_Bebop(void)
virtual void printf(const char *,...) FMT_PRINTF(2
AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state)
virtual OwnPtr< SPIDevice > get_device(const char *name)
#define RNFD_BEBOP_NB_PULSES_MAX
bool is_zero(const T fVal1)
#define RNFD_BEBOP_NB_PULSES_PURGE
int _search_local_maxima(void)
#define RNFD_BEBOP_TRANSITION_COUNT
AP_HAL::SPIDeviceManager * spi
#define RNFD_BEBOP_DEFAULT_ADC_FREQ
#define RNFD_BEBOP_TRANSITION_HIGH_TO_LOW
int errno
Note: fdevopen assigns stdin,stdout,stderr.
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void panic(const char *errormsg,...) FMT_PRINTF(1
RangeFinder::RangeFinder_State & state
#define RNFD_BEBOP_SOUND_SPEED
int _apply_averaging_filter(void)
int _search_maximum_with_max_amplitude(void)