9 #ifndef CENTRAL_DATA_H_
10 #define CENTRAL_DATA_H_
17 #include "time_keeper.h"
23 #include "stabilisation_copter.h"
26 #include "pid_controller.h"
29 #include "print_util.h"
32 #include "mavlink_stream.h"
33 #include "coord_conventions.h"
34 #include "onboard_parameters.h"
35 #include "servo_pwm.h"
37 #include "gps_ublox.h"
38 #include "mavlink_waypoint_handler.h"
39 #include "simulation.h"
41 #include "conf_sim_model.h"
42 #include "position_estimation.h"
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}};
46 enum CRITICAL_BEHAVIOR_ENUM{
47 CLIMB_TO_SAFE_ALT = 1,
61 buffer_t xbee_in_buffer, wired_in_buffer;
81 uint16_t number_of_waypoints;
82 int8_t current_wp_count;
84 local_coordinates_t waypoint_coordinates, waypoint_hold_coordinates, waypoint_critical_coordinates;
88 bool waypoint_sending;
89 bool waypoint_receiving;
90 bool waypoint_handler_waypoint_hold_init;
91 bool critical_landing;
92 bool critical_next_state;
94 bool collision_avoidance;
95 bool automatic_take_off;
100 uint8_t mav_mode_previous;
101 uint8_t mav_state_previous;
103 uint32_t simulation_mode;
110 enum CRITICAL_BEHAVIOR_ENUM critical_behavior;
115 void central_data_init(
void);
122 imu_t* get_imu_data();
125 #define STDOUT &print_util_get_debug_stream()
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