MAV'RIC
central_data.h
1 /*
2  * central_data.h
3  *
4  * Created: 16/09/2013 12:18:00
5  * Author: sfx
6  */
7 
8 
9 #ifndef CENTRAL_DATA_H_
10 #define CENTRAL_DATA_H_
11 
12 #include <stdbool.h>
13 #include <stdint.h>
14 
15 #include "stdbool.h"
16 
17 #include "time_keeper.h"
18 //#include "i2c_driver_int.h"
19 #include "qfilter.h"
20 #include "imu.h"
21 
22 // #include "stabilisation.h"
23 #include "stabilisation_copter.h"
24 // #include "stabilisation_hybrid.h"
25 
26 #include "pid_controller.h"
27 #include "streams.h"
28 //#include "uart_int.h"
29 #include "print_util.h"
30 
31 #include "bmp085.h"
32 #include "mavlink_stream.h"
33 #include "coord_conventions.h"
34 #include "onboard_parameters.h"
35 #include "servo_pwm.h"
36 
37 #include "gps_ublox.h"
38 #include "mavlink_waypoint_handler.h"
39 #include "simulation.h"
40 #include "bmp085.h"
41 #include "conf_sim_model.h"
42 #include "position_estimation.h"
43 
44 static const servo_output_t servo_failsafe[NUMBER_OF_SERVO_OUTPUTS]={{.value=-600}, {.value=-600}, {.value=-600}, {.value=-600}, {.value=-600}, {.value=-600}, {.value=-600}, {.value=-600}};
45 
46 enum CRITICAL_BEHAVIOR_ENUM{
47  CLIMB_TO_SAFE_ALT = 1,
48  FLY_TO_HOME_WP = 2,
49  CRITICAL_LAND = 3,
50 };
51 
52 typedef struct {
53  imu_t imu;
54  control_command_t controls;
55  control_command_t controls_nav;
56 
57  stabiliser_stack_copter_t stabiliser_stack;
58 
59  simulation_model_t uav_model;
60  servo_output_t servos[NUMBER_OF_SERVO_OUTPUTS];
61  buffer_t xbee_in_buffer, wired_in_buffer;
62  byte_stream_t xbee_out_stream;
63  byte_stream_t xbee_in_stream;
64  byte_stream_t wired_out_stream, wired_in_stream;
65 
66  buffer_t gps_buffer;
67  byte_stream_t gps_stream_in;
68  byte_stream_t gps_stream_out;
69  gps_t gps;
70 
71  simulation_model_t sim_model;
72 
73  position_estimation_t position_estimation;
74 
75  // aliases
76  byte_stream_t *telemetry_down_stream, *telemetry_up_stream;
77  byte_stream_t *debug_out_stream, *debug_in_stream;
78 
79  waypoint_struct_t waypoint_list[MAX_WAYPOINTS];
80  waypoint_struct_t current_waypoint;
81  uint16_t number_of_waypoints;
82  int8_t current_wp_count;
83 
84  local_coordinates_t waypoint_coordinates, waypoint_hold_coordinates, waypoint_critical_coordinates;
85  float dist2wp_sqr;
86 
87  bool waypoint_set;
88  bool waypoint_sending;
89  bool waypoint_receiving;
90  bool waypoint_handler_waypoint_hold_init;
91  bool critical_landing;
92  bool critical_next_state;
93 
94  bool collision_avoidance;
95  bool automatic_take_off;
96 
97  uint8_t mav_mode;
98  uint8_t mav_state;
99 
100  uint8_t mav_mode_previous;
101  uint8_t mav_state_previous;
102 
103  uint32_t simulation_mode;
104 
105  barometer_t pressure;
106  //float pressure_filtered;
107  //float altitude_filtered;
108 
109 
110  enum CRITICAL_BEHAVIOR_ENUM critical_behavior;
111 
113 
114 
115 void central_data_init(void);
116 
117 central_data_t* central_data_get_pointer_to_struct(void);
118 
119 byte_stream_t* get_telemetry_upstream(void);
120 byte_stream_t* get_telemetry_downstream(void);
121 
122 imu_t* get_imu_data();
123 control_command_t* get_control_inputs_data();
124 
125 #define STDOUT &print_util_get_debug_stream()
126 
127 #endif /* CENTRAL_DATA_H_ */
The MAVLink waypoint structure.
Definition: mavlink_waypoint_handler.h:68
Buffer structure.
Definition: buffer.h:61
Structure containing the stacked controller.
Definition: stabilisation_copter.h:70
The simulation model structure definition.
Definition: simulation.h:99
The control command typedef.
Definition: stabilisation.h:77
Definition: servo_pwm.h:22
Type definition for GPS data.
Definition: gps_ublox.h:635
The IMU structure.
Definition: imu.h:108
Definition: central_data.h:52
Byte stream.
Definition: streams.h:62
Define the barometer structure.
Definition: barometer.h:60
Local coordinates structure.
Definition: coord_conventions.h:73
The position estimator structure.
Definition: position_estimation.h:79