APM:Libraries
AP_Module_Structures.h
Go to the documentation of this file.
1 /*
2  this defines data structures for public module interfaces in
3  ArduPilot.
4 
5  These structures are designed to not depend on other headers inside
6  ArduPilot, although they do depend on the general ABI of the
7  platform, and thus can depend on compilation options to some extent
8  */
9 
10 #ifdef __cplusplus
11 extern "C" {
12 #endif
13 
14 #include <stdint.h>
15 #include <stdbool.h>
16 
17 #define AHRS_state_version 3
18 #define gyro_sample_version 1
19 #define accel_sample_version 2
20 
25 };
26 
27 /*
28  export the attitude and position of the vehicle.
29  */
30 struct AHRS_state {
31  // version of this structure (AHRS_state_version)
33 
34  // time since boot in microseconds
35  uint64_t time_us;
36 
37  // status of AHRS solution
39 
40  // quaternion attitude, first element is length scalar. Same
41  // conventions as AP_Math/quaternion.h
42  float quat[4];
43 
44  // euler angles in radians. Order is roll, pitch, yaw
45  float eulers[3];
46 
47  // global origin
48  struct {
49  // true when origin has been initialised with a global position
51 
52  // latitude and longitude in degrees * 10^7 (approx 1cm resolution)
53  int32_t latitude;
54  int32_t longitude;
55 
56  // altitude AMSL in meters, positive up
57  float altitude;
58  } origin;
59 
60  // global position
61  struct {
62  // true when we have a global position
63  bool available;
64 
65  // latitude and longitude in degrees * 10^7 (approx 1cm resolution)
66  int32_t latitude;
67  int32_t longitude;
68 
69  // altitude AMSL in meters, positive up
70  float altitude;
71  } position;
72 
73  // NED relative position in meters. Relative to origin
75 
76  // current rotational rates in radians/second in body frame
77  // order is roll, pitch, yaw
78  float gyro_rate[3];
79 
80  // current earth frame acceleration estimate, including
81  // gravitational forces, m/s/s order is NED
82  float accel_ef[3];
83 
84  // the current primary accel instance
85  uint8_t primary_accel;
86 
87  // the current primary gyro instance
88  uint8_t primary_gyro;
89 
90  // current gyro bias. This is relative to the gyro data in
91  // gyro_sample for primary_gyro. It should be added to a gyro
92  // sample to get the corrected gyro estimate
93  float gyro_bias[3];
94 
95  // north-east-down velocity m/s
96  float velocity_ned[3];
97 };
98 
99 
100 /*
101  export corrected gyro samples at hardware sampling rate
102  */
103 struct gyro_sample {
104  // version of this structure (gyro_sample_version)
106 
107  // which gyro this is
108  uint8_t instance;
109 
110  // time since boot in microseconds
111  uint64_t time_us;
112 
113  // time associated with this sample (seconds)
114  float delta_time;
115 
116  // body frame rates in radian/sec
117  float gyro[3];
118 };
119 
120 /*
121  export corrected accel samples at hardware sampling rate
122  */
123 struct accel_sample {
124  // version of this structure (accel_sample_version)
126 
127  // which accel this is
128  uint8_t instance;
129 
130  // time since boot in microseconds
131  uint64_t time_us;
132 
133  // time associated with this sample (seconds)
134  float delta_time;
135 
136  // body frame rates in m/s/s
137  float accel[3];
138 
139  // true if external frame sync is set
140  bool fsync_set;
141 };
142 
143 /*
144  prototypes for hook functions
145  */
146 typedef void (*ap_hook_setup_start_fn_t)(uint64_t);
147 void ap_hook_setup_start(uint64_t time_us);
148 
149 typedef void (*ap_hook_setup_complete_fn_t)(uint64_t);
150 void ap_hook_setup_complete(uint64_t time_us);
151 
152 typedef void (*ap_hook_AHRS_update_fn_t)(const struct AHRS_state *);
153 void ap_hook_AHRS_update(const struct AHRS_state *state);
154 
155 typedef void (*ap_hook_gyro_sample_fn_t)(const struct gyro_sample *);
156 void ap_hook_gyro_sample(const struct gyro_sample *state);
157 
158 typedef void (*ap_hook_accel_sample_fn_t)(const struct accel_sample *);
159 void ap_hook_accel_sample(const struct accel_sample *state);
160 
161 #ifdef __cplusplus
162 }
163 #endif
164 
void ap_hook_AHRS_update(const struct AHRS_state *state)
Definition: moduletest.c:25
void ap_hook_gyro_sample(const struct gyro_sample *state)
Definition: moduletest.c:39
uint32_t structure_version
uint32_t structure_version
void(* ap_hook_AHRS_update_fn_t)(const struct AHRS_state *)
float relative_position[3]
uint32_t structure_version
void ap_hook_setup_complete(uint64_t time_us)
Definition: moduletest.c:17
enum AHRS_status status
void(* ap_hook_gyro_sample_fn_t)(const struct gyro_sample *)
static int state
Definition: Util.cpp:20
void ap_hook_setup_start(uint64_t time_us)
Definition: moduletest.c:12
struct AHRS_state::@133 origin
void ap_hook_accel_sample(const struct accel_sample *state)
Definition: moduletest.c:53
struct AHRS_state::@134 position
void(* ap_hook_setup_complete_fn_t)(uint64_t)
void(* ap_hook_accel_sample_fn_t)(const struct accel_sample *)
float velocity_ned[3]
void(* ap_hook_setup_start_fn_t)(uint64_t)