APM:Libraries
AP_RangeFinder_Bebop.h
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 #pragma once
16 
17 #include "RangeFinder.h"
18 #include "RangeFinder_Backend.h"
19 #include <AP_HAL_Linux/Thread.h>
20 
21 /*
22  * the size of the buffer sent over spi
23  */
24 #define RNFD_BEBOP_NB_PULSES_MAX 32
25 
26 /*
27  * the size of the purge buffer sent over spi
28  */
29 #define RNFD_BEBOP_NB_PULSES_PURGE 64
30 
31 /*
32  * default us frequency
33  * 17 times by seconds
34  */
35 #define RNFD_BEBOP_DEFAULT_FREQ 17
36 
37 /*
38  * default adc frequency
39  */
40 #define RNFD_BEBOP_DEFAULT_ADC_FREQ 160000
41 
42 /*
43  * to filter data we make the average of (1 << this_value) datas
44  */
45 #define RNFD_BEBOP_FILTER_POWER 2
46 
47 /*
48  * Speed of sound
49  */
50 #define RNFD_BEBOP_SOUND_SPEED 340
51 
52 /* above this altitude we should use mode 0 */
53 #define RNFD_BEBOP_TRANSITION_HIGH_TO_LOW 0.75
54 
55 /* below this altitude we should use mode 1 */
56 #define RNFD_BEBOP_TRANSITION_LOW_TO_HIGH 1.5
57 
58 /* count this times before switching mode */
59 #define RNFD_BEBOP_TRANSITION_COUNT 5
60 
61 /*
62  * the number of echoes we will keep at most
63  */
64 #define RNFD_BEBOP_MAX_ECHOES 30
65 
66 struct echo {
67  int max_index; /* index in the capture buffer at which the maximum is reached */
68  int distance_index; /* index in the capture buffer at which the signal is for
69  the first time above a fixed threshold below the
70  maximum => this corresponds to the real distance
71  that should be attributed to this echo */
72 };
73 
74 /*
75  * struct related to adc
76  * data to receive and process adc datas
77  */
78 struct adc_capture {
79  struct iio_device *device;
80  struct iio_buffer *buffer;
81  unsigned int buffer_size;
82  struct iio_channel *channel;
83  unsigned int freq;
84 
85  /* Used in order to match two echoes of two ADC acquisitions */
86  unsigned short threshold_time_rejection;
87 };
88 
90 public:
92 
93  ~AP_RangeFinder_Bebop(void);
94  static bool detect();
95  void update(void);
96 
97 protected:
98 
99  virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const {
100  return MAV_DISTANCE_SENSOR_LASER;
101  }
102 
103 private:
104  void _init(void);
105  int _launch(void);
106  int _capture(void);
107  int _update_mode(float altitude);
108  void _configure_gpio(int value);
109  int _configure_wave();
110  void _reconfigure_wave();
111  int _configure_capture();
112  int _launch_purge();
113  void _loop(void);
114 
116  unsigned short get_threshold_at(int i_capture);
117  int _apply_averaging_filter(void);
118  int _search_local_maxima(void);
119  int _search_maximum_with_max_amplitude(void);
120 
123 
124  struct adc_capture _adc;
125  struct iio_context *_iio;
126 
127  unsigned char _tx[2][RNFD_BEBOP_NB_PULSES_MAX];
128  unsigned char _purge[RNFD_BEBOP_NB_PULSES_PURGE];
129  unsigned char* _tx_buf;
131  const unsigned int threshold_echo_init = 1500;
132  int _fd = -1;
133  uint64_t _last_timestamp;
134  int _mode;
136  int _freq;
137  float _altitude;
138  unsigned int *_filtered_capture;
140  struct echo _echoes[RNFD_BEBOP_MAX_ECHOES];
141  unsigned int _filter_average = 4;
142  int16_t _last_max_distance_cm = 850;
143  int16_t _last_min_distance_cm = 32;
144 };
145 
struct iio_buffer * buffer
struct iio_context * _iio
unsigned int freq
#define RNFD_BEBOP_MAX_ECHOES
unsigned int * _filtered_capture
struct iio_device * device
unsigned short threshold_time_rejection
int distance_index
#define RNFD_BEBOP_NB_PULSES_MAX
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const
#define RNFD_BEBOP_NB_PULSES_PURGE
AP_HAL::OwnPtr< AP_HAL::Device > _spi
struct iio_channel * channel
unsigned int buffer_size
float value
unsigned int _filtered_capture_size