57 #include "position_estimation.h"
59 #include "navigation.h"
60 #include "stabilisation_copter.h"
61 #include "stabilisation.h"
62 #include "mavlink_waypoint_handler.h"
67 #define RELIABILITY_ARC 0.25f
69 #define MAX_DETECTION_RANGE 100
113 void acoustic_init(
audio_t* audio_data,
132 task_return_t acoustic_update(
audio_t* audio_data);
153 void acoustic_set_speed_command(
audio_t* audio_data,
float rel_pos[],
float dist2wpSqr);
bool reliabe_data
The flag to tell that new data are reliable.
Definition: acoustic.h:80
Structure containing the Attitude and Heading Reference System.
Definition: ahrs.h:58
mavlink_waypoint_handler_t * waypoint_handler
The pointer to the waypoint handler structure.
Definition: acoustic.h:94
float reliabe_az
Number of reliable azimuth measurement.
Definition: acoustic.h:81
The configuration structure of the remote.
Definition: remote.h:150
ahrs_t * ahrs
The pointer to the attitude estimation structure.
Definition: acoustic.h:88
The navigation structure.
Definition: navigation.h:66
int16_t elevation
The elevation angle corresponds to the vertical orientation of the sound.
Definition: acoustic.h:78
byte_stream_t audio_stream_in
Acoustic in coming stream.
Definition: acoustic.h:85
Buffer structure.
Definition: buffer.h:61
Structure containing the pointers to the data needed in this module.
Definition: stabilisation_copter.h:82
bool new_data
The flag to tell that new data are available.
Definition: acoustic.h:79
The control command typedef.
Definition: stabilisation.h:77
stabilisation_copter_t * stabilisation_copter
The pointer to the stabilization copter structure.
Definition: acoustic.h:92
buffer_t audio_buffer
Acoustic buffer.
Definition: acoustic.h:84
Structure of the acoustic data.
Definition: acoustic.h:75
remote_t * remote
The pointer to the remote structure.
Definition: acoustic.h:90
int16_t azimuth
The azimuth angle corresponds to the horizontal orientation of the sound.
Definition: acoustic.h:77
Definition: mavlink_waypoint_handler.h:83
position_estimation_t * position_estimation
The pointer to the position estimation structure.
Definition: acoustic.h:89
Byte stream.
Definition: streams.h:62
byte_stream_t * telemetry_down_stream
The pointer to the down coming telemetry byte stream.
Definition: acoustic.h:95
float reliabe_el
Number of reliable elevation measurement.
Definition: acoustic.h:82
control_command_t * controls_nav
The pointer to the control structure.
Definition: acoustic.h:93
The position estimator structure.
Definition: position_estimation.h:79
navigation_t * navigation
The pointer to the navigation control structure.
Definition: acoustic.h:91