24 #define RNFD_BEBOP_NB_PULSES_MAX 32 29 #define RNFD_BEBOP_NB_PULSES_PURGE 64 35 #define RNFD_BEBOP_DEFAULT_FREQ 17 40 #define RNFD_BEBOP_DEFAULT_ADC_FREQ 160000 45 #define RNFD_BEBOP_FILTER_POWER 2 50 #define RNFD_BEBOP_SOUND_SPEED 340 53 #define RNFD_BEBOP_TRANSITION_HIGH_TO_LOW 0.75 56 #define RNFD_BEBOP_TRANSITION_LOW_TO_HIGH 1.5 59 #define RNFD_BEBOP_TRANSITION_COUNT 5 64 #define RNFD_BEBOP_MAX_ECHOES 30 100 return MAV_DISTANCE_SENSOR_LASER;
107 int _update_mode(
float altitude);
108 void _configure_gpio(
int value);
109 int _configure_wave();
110 void _reconfigure_wave();
111 int _configure_capture();
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);
131 const unsigned int threshold_echo_init = 1500;
141 unsigned int _filter_average = 4;
142 int16_t _last_max_distance_cm = 850;
143 int16_t _last_min_distance_cm = 32;
struct iio_buffer * buffer
struct iio_context * _iio
#define RNFD_BEBOP_MAX_ECHOES
unsigned int * _filtered_capture
struct iio_device * device
unsigned short threshold_time_rejection
#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 _filtered_capture_size