1 | // MESSAGE GLOBAL_POSITION_INT_COV PACKING
|
---|
2 |
|
---|
3 | #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63
|
---|
4 |
|
---|
5 | typedef struct MAVLINK_PACKED __mavlink_global_position_int_cov_t
|
---|
6 | {
|
---|
7 | uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.*/
|
---|
8 | uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
|
---|
9 | int32_t lat; /*< Latitude, expressed as degrees * 1E7*/
|
---|
10 | int32_t lon; /*< Longitude, expressed as degrees * 1E7*/
|
---|
11 | int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/
|
---|
12 | int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/
|
---|
13 | float vx; /*< Ground X Speed (Latitude), expressed as m/s*/
|
---|
14 | float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/
|
---|
15 | float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/
|
---|
16 | float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/
|
---|
17 | uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
|
---|
18 | } mavlink_global_position_int_cov_t;
|
---|
19 |
|
---|
20 | #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185
|
---|
21 | #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN 185
|
---|
22 | #define MAVLINK_MSG_ID_63_LEN 185
|
---|
23 | #define MAVLINK_MSG_ID_63_MIN_LEN 185
|
---|
24 |
|
---|
25 | #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51
|
---|
26 | #define MAVLINK_MSG_ID_63_CRC 51
|
---|
27 |
|
---|
28 | #define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36
|
---|
29 |
|
---|
30 | #if MAVLINK_COMMAND_24BIT
|
---|
31 | #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
|
---|
32 | 63, \
|
---|
33 | "GLOBAL_POSITION_INT_COV", \
|
---|
34 | 11, \
|
---|
35 | { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \
|
---|
36 | { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \
|
---|
37 | { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \
|
---|
38 | { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \
|
---|
39 | { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \
|
---|
40 | { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
|
---|
41 | { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \
|
---|
42 | { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \
|
---|
43 | { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \
|
---|
44 | { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
|
---|
45 | { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
|
---|
46 | } \
|
---|
47 | }
|
---|
48 | #else
|
---|
49 | #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
|
---|
50 | "GLOBAL_POSITION_INT_COV", \
|
---|
51 | 11, \
|
---|
52 | { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \
|
---|
53 | { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \
|
---|
54 | { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \
|
---|
55 | { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \
|
---|
56 | { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \
|
---|
57 | { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
|
---|
58 | { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \
|
---|
59 | { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \
|
---|
60 | { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \
|
---|
61 | { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
|
---|
62 | { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
|
---|
63 | } \
|
---|
64 | }
|
---|
65 | #endif
|
---|
66 |
|
---|
67 | /**
|
---|
68 | * @brief Pack a global_position_int_cov message
|
---|
69 | * @param system_id ID of this system
|
---|
70 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
71 | * @param msg The MAVLink message to compress the data into
|
---|
72 | *
|
---|
73 | * @param time_boot_ms Timestamp (milliseconds since system boot)
|
---|
74 | * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
75 | * @param estimator_type Class id of the estimator this estimate originated from.
|
---|
76 | * @param lat Latitude, expressed as degrees * 1E7
|
---|
77 | * @param lon Longitude, expressed as degrees * 1E7
|
---|
78 | * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
|
---|
79 | * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
|
---|
80 | * @param vx Ground X Speed (Latitude), expressed as m/s
|
---|
81 | * @param vy Ground Y Speed (Longitude), expressed as m/s
|
---|
82 | * @param vz Ground Z Speed (Altitude), expressed as m/s
|
---|
83 | * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
|
---|
84 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
85 | */
|
---|
86 | static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
87 | uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
|
---|
88 | {
|
---|
89 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
90 | char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
|
---|
91 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
92 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
93 | _mav_put_int32_t(buf, 12, lat);
|
---|
94 | _mav_put_int32_t(buf, 16, lon);
|
---|
95 | _mav_put_int32_t(buf, 20, alt);
|
---|
96 | _mav_put_int32_t(buf, 24, relative_alt);
|
---|
97 | _mav_put_float(buf, 28, vx);
|
---|
98 | _mav_put_float(buf, 32, vy);
|
---|
99 | _mav_put_float(buf, 36, vz);
|
---|
100 | _mav_put_uint8_t(buf, 184, estimator_type);
|
---|
101 | _mav_put_float_array(buf, 40, covariance, 36);
|
---|
102 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
---|
103 | #else
|
---|
104 | mavlink_global_position_int_cov_t packet;
|
---|
105 | packet.time_utc = time_utc;
|
---|
106 | packet.time_boot_ms = time_boot_ms;
|
---|
107 | packet.lat = lat;
|
---|
108 | packet.lon = lon;
|
---|
109 | packet.alt = alt;
|
---|
110 | packet.relative_alt = relative_alt;
|
---|
111 | packet.vx = vx;
|
---|
112 | packet.vy = vy;
|
---|
113 | packet.vz = vz;
|
---|
114 | packet.estimator_type = estimator_type;
|
---|
115 | mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
|
---|
116 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
---|
117 | #endif
|
---|
118 |
|
---|
119 | msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
|
---|
120 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
---|
121 | }
|
---|
122 |
|
---|
123 | /**
|
---|
124 | * @brief Pack a global_position_int_cov message on a channel
|
---|
125 | * @param system_id ID of this system
|
---|
126 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
127 | * @param chan The MAVLink channel this message will be sent over
|
---|
128 | * @param msg The MAVLink message to compress the data into
|
---|
129 | * @param time_boot_ms Timestamp (milliseconds since system boot)
|
---|
130 | * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
131 | * @param estimator_type Class id of the estimator this estimate originated from.
|
---|
132 | * @param lat Latitude, expressed as degrees * 1E7
|
---|
133 | * @param lon Longitude, expressed as degrees * 1E7
|
---|
134 | * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
|
---|
135 | * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
|
---|
136 | * @param vx Ground X Speed (Latitude), expressed as m/s
|
---|
137 | * @param vy Ground Y Speed (Longitude), expressed as m/s
|
---|
138 | * @param vz Ground Z Speed (Altitude), expressed as m/s
|
---|
139 | * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
|
---|
140 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
141 | */
|
---|
142 | static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
143 | mavlink_message_t* msg,
|
---|
144 | uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance)
|
---|
145 | {
|
---|
146 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
147 | char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
|
---|
148 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
149 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
150 | _mav_put_int32_t(buf, 12, lat);
|
---|
151 | _mav_put_int32_t(buf, 16, lon);
|
---|
152 | _mav_put_int32_t(buf, 20, alt);
|
---|
153 | _mav_put_int32_t(buf, 24, relative_alt);
|
---|
154 | _mav_put_float(buf, 28, vx);
|
---|
155 | _mav_put_float(buf, 32, vy);
|
---|
156 | _mav_put_float(buf, 36, vz);
|
---|
157 | _mav_put_uint8_t(buf, 184, estimator_type);
|
---|
158 | _mav_put_float_array(buf, 40, covariance, 36);
|
---|
159 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
---|
160 | #else
|
---|
161 | mavlink_global_position_int_cov_t packet;
|
---|
162 | packet.time_utc = time_utc;
|
---|
163 | packet.time_boot_ms = time_boot_ms;
|
---|
164 | packet.lat = lat;
|
---|
165 | packet.lon = lon;
|
---|
166 | packet.alt = alt;
|
---|
167 | packet.relative_alt = relative_alt;
|
---|
168 | packet.vx = vx;
|
---|
169 | packet.vy = vy;
|
---|
170 | packet.vz = vz;
|
---|
171 | packet.estimator_type = estimator_type;
|
---|
172 | mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
|
---|
173 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
---|
174 | #endif
|
---|
175 |
|
---|
176 | msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
|
---|
177 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
---|
178 | }
|
---|
179 |
|
---|
180 | /**
|
---|
181 | * @brief Encode a global_position_int_cov struct
|
---|
182 | *
|
---|
183 | * @param system_id ID of this system
|
---|
184 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
185 | * @param msg The MAVLink message to compress the data into
|
---|
186 | * @param global_position_int_cov C-struct to read the message contents from
|
---|
187 | */
|
---|
188 | static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
|
---|
189 | {
|
---|
190 | return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
|
---|
191 | }
|
---|
192 |
|
---|
193 | /**
|
---|
194 | * @brief Encode a global_position_int_cov struct on a channel
|
---|
195 | *
|
---|
196 | * @param system_id ID of this system
|
---|
197 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
198 | * @param chan The MAVLink channel this message will be sent over
|
---|
199 | * @param msg The MAVLink message to compress the data into
|
---|
200 | * @param global_position_int_cov C-struct to read the message contents from
|
---|
201 | */
|
---|
202 | static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
|
---|
203 | {
|
---|
204 | return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
|
---|
205 | }
|
---|
206 |
|
---|
207 | /**
|
---|
208 | * @brief Send a global_position_int_cov message
|
---|
209 | * @param chan MAVLink channel to send the message
|
---|
210 | *
|
---|
211 | * @param time_boot_ms Timestamp (milliseconds since system boot)
|
---|
212 | * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
213 | * @param estimator_type Class id of the estimator this estimate originated from.
|
---|
214 | * @param lat Latitude, expressed as degrees * 1E7
|
---|
215 | * @param lon Longitude, expressed as degrees * 1E7
|
---|
216 | * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
|
---|
217 | * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
|
---|
218 | * @param vx Ground X Speed (Latitude), expressed as m/s
|
---|
219 | * @param vy Ground Y Speed (Longitude), expressed as m/s
|
---|
220 | * @param vz Ground Z Speed (Altitude), expressed as m/s
|
---|
221 | * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
|
---|
222 | */
|
---|
223 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
224 |
|
---|
225 | static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
|
---|
226 | {
|
---|
227 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
228 | char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
|
---|
229 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
230 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
231 | _mav_put_int32_t(buf, 12, lat);
|
---|
232 | _mav_put_int32_t(buf, 16, lon);
|
---|
233 | _mav_put_int32_t(buf, 20, alt);
|
---|
234 | _mav_put_int32_t(buf, 24, relative_alt);
|
---|
235 | _mav_put_float(buf, 28, vx);
|
---|
236 | _mav_put_float(buf, 32, vy);
|
---|
237 | _mav_put_float(buf, 36, vz);
|
---|
238 | _mav_put_uint8_t(buf, 184, estimator_type);
|
---|
239 | _mav_put_float_array(buf, 40, covariance, 36);
|
---|
240 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
---|
241 | #else
|
---|
242 | mavlink_global_position_int_cov_t packet;
|
---|
243 | packet.time_utc = time_utc;
|
---|
244 | packet.time_boot_ms = time_boot_ms;
|
---|
245 | packet.lat = lat;
|
---|
246 | packet.lon = lon;
|
---|
247 | packet.alt = alt;
|
---|
248 | packet.relative_alt = relative_alt;
|
---|
249 | packet.vx = vx;
|
---|
250 | packet.vy = vy;
|
---|
251 | packet.vz = vz;
|
---|
252 | packet.estimator_type = estimator_type;
|
---|
253 | mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
|
---|
254 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
---|
255 | #endif
|
---|
256 | }
|
---|
257 |
|
---|
258 | /**
|
---|
259 | * @brief Send a global_position_int_cov message
|
---|
260 | * @param chan MAVLink channel to send the message
|
---|
261 | * @param struct The MAVLink struct to serialize
|
---|
262 | */
|
---|
263 | static inline void mavlink_msg_global_position_int_cov_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_cov_t* global_position_int_cov)
|
---|
264 | {
|
---|
265 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
266 | mavlink_msg_global_position_int_cov_send(chan, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
|
---|
267 | #else
|
---|
268 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)global_position_int_cov, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
---|
269 | #endif
|
---|
270 | }
|
---|
271 |
|
---|
272 | #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
273 | /*
|
---|
274 | This varient of _send() can be used to save stack space by re-using
|
---|
275 | memory from the receive buffer. The caller provides a
|
---|
276 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
277 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
278 | incoming message with minimum stack space usage.
|
---|
279 | */
|
---|
280 | static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
|
---|
281 | {
|
---|
282 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
283 | char *buf = (char *)msgbuf;
|
---|
284 | _mav_put_uint64_t(buf, 0, time_utc);
|
---|
285 | _mav_put_uint32_t(buf, 8, time_boot_ms);
|
---|
286 | _mav_put_int32_t(buf, 12, lat);
|
---|
287 | _mav_put_int32_t(buf, 16, lon);
|
---|
288 | _mav_put_int32_t(buf, 20, alt);
|
---|
289 | _mav_put_int32_t(buf, 24, relative_alt);
|
---|
290 | _mav_put_float(buf, 28, vx);
|
---|
291 | _mav_put_float(buf, 32, vy);
|
---|
292 | _mav_put_float(buf, 36, vz);
|
---|
293 | _mav_put_uint8_t(buf, 184, estimator_type);
|
---|
294 | _mav_put_float_array(buf, 40, covariance, 36);
|
---|
295 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
---|
296 | #else
|
---|
297 | mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf;
|
---|
298 | packet->time_utc = time_utc;
|
---|
299 | packet->time_boot_ms = time_boot_ms;
|
---|
300 | packet->lat = lat;
|
---|
301 | packet->lon = lon;
|
---|
302 | packet->alt = alt;
|
---|
303 | packet->relative_alt = relative_alt;
|
---|
304 | packet->vx = vx;
|
---|
305 | packet->vy = vy;
|
---|
306 | packet->vz = vz;
|
---|
307 | packet->estimator_type = estimator_type;
|
---|
308 | mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
|
---|
309 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
---|
310 | #endif
|
---|
311 | }
|
---|
312 | #endif
|
---|
313 |
|
---|
314 | #endif
|
---|
315 |
|
---|
316 | // MESSAGE GLOBAL_POSITION_INT_COV UNPACKING
|
---|
317 |
|
---|
318 |
|
---|
319 | /**
|
---|
320 | * @brief Get field time_boot_ms from global_position_int_cov message
|
---|
321 | *
|
---|
322 | * @return Timestamp (milliseconds since system boot)
|
---|
323 | */
|
---|
324 | static inline uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms(const mavlink_message_t* msg)
|
---|
325 | {
|
---|
326 | return _MAV_RETURN_uint32_t(msg, 8);
|
---|
327 | }
|
---|
328 |
|
---|
329 | /**
|
---|
330 | * @brief Get field time_utc from global_position_int_cov message
|
---|
331 | *
|
---|
332 | * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
---|
333 | */
|
---|
334 | static inline uint64_t mavlink_msg_global_position_int_cov_get_time_utc(const mavlink_message_t* msg)
|
---|
335 | {
|
---|
336 | return _MAV_RETURN_uint64_t(msg, 0);
|
---|
337 | }
|
---|
338 |
|
---|
339 | /**
|
---|
340 | * @brief Get field estimator_type from global_position_int_cov message
|
---|
341 | *
|
---|
342 | * @return Class id of the estimator this estimate originated from.
|
---|
343 | */
|
---|
344 | static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg)
|
---|
345 | {
|
---|
346 | return _MAV_RETURN_uint8_t(msg, 184);
|
---|
347 | }
|
---|
348 |
|
---|
349 | /**
|
---|
350 | * @brief Get field lat from global_position_int_cov message
|
---|
351 | *
|
---|
352 | * @return Latitude, expressed as degrees * 1E7
|
---|
353 | */
|
---|
354 | static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg)
|
---|
355 | {
|
---|
356 | return _MAV_RETURN_int32_t(msg, 12);
|
---|
357 | }
|
---|
358 |
|
---|
359 | /**
|
---|
360 | * @brief Get field lon from global_position_int_cov message
|
---|
361 | *
|
---|
362 | * @return Longitude, expressed as degrees * 1E7
|
---|
363 | */
|
---|
364 | static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg)
|
---|
365 | {
|
---|
366 | return _MAV_RETURN_int32_t(msg, 16);
|
---|
367 | }
|
---|
368 |
|
---|
369 | /**
|
---|
370 | * @brief Get field alt from global_position_int_cov message
|
---|
371 | *
|
---|
372 | * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
|
---|
373 | */
|
---|
374 | static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg)
|
---|
375 | {
|
---|
376 | return _MAV_RETURN_int32_t(msg, 20);
|
---|
377 | }
|
---|
378 |
|
---|
379 | /**
|
---|
380 | * @brief Get field relative_alt from global_position_int_cov message
|
---|
381 | *
|
---|
382 | * @return Altitude above ground in meters, expressed as * 1000 (millimeters)
|
---|
383 | */
|
---|
384 | static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg)
|
---|
385 | {
|
---|
386 | return _MAV_RETURN_int32_t(msg, 24);
|
---|
387 | }
|
---|
388 |
|
---|
389 | /**
|
---|
390 | * @brief Get field vx from global_position_int_cov message
|
---|
391 | *
|
---|
392 | * @return Ground X Speed (Latitude), expressed as m/s
|
---|
393 | */
|
---|
394 | static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg)
|
---|
395 | {
|
---|
396 | return _MAV_RETURN_float(msg, 28);
|
---|
397 | }
|
---|
398 |
|
---|
399 | /**
|
---|
400 | * @brief Get field vy from global_position_int_cov message
|
---|
401 | *
|
---|
402 | * @return Ground Y Speed (Longitude), expressed as m/s
|
---|
403 | */
|
---|
404 | static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg)
|
---|
405 | {
|
---|
406 | return _MAV_RETURN_float(msg, 32);
|
---|
407 | }
|
---|
408 |
|
---|
409 | /**
|
---|
410 | * @brief Get field vz from global_position_int_cov message
|
---|
411 | *
|
---|
412 | * @return Ground Z Speed (Altitude), expressed as m/s
|
---|
413 | */
|
---|
414 | static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg)
|
---|
415 | {
|
---|
416 | return _MAV_RETURN_float(msg, 36);
|
---|
417 | }
|
---|
418 |
|
---|
419 | /**
|
---|
420 | * @brief Get field covariance from global_position_int_cov message
|
---|
421 | *
|
---|
422 | * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
|
---|
423 | */
|
---|
424 | static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
|
---|
425 | {
|
---|
426 | return _MAV_RETURN_float_array(msg, covariance, 36, 40);
|
---|
427 | }
|
---|
428 |
|
---|
429 | /**
|
---|
430 | * @brief Decode a global_position_int_cov message into a struct
|
---|
431 | *
|
---|
432 | * @param msg The message to decode
|
---|
433 | * @param global_position_int_cov C-struct to decode the message contents into
|
---|
434 | */
|
---|
435 | static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov)
|
---|
436 | {
|
---|
437 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
438 | global_position_int_cov->time_utc = mavlink_msg_global_position_int_cov_get_time_utc(msg);
|
---|
439 | global_position_int_cov->time_boot_ms = mavlink_msg_global_position_int_cov_get_time_boot_ms(msg);
|
---|
440 | global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg);
|
---|
441 | global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg);
|
---|
442 | global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg);
|
---|
443 | global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg);
|
---|
444 | global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg);
|
---|
445 | global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg);
|
---|
446 | global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg);
|
---|
447 | mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance);
|
---|
448 | global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg);
|
---|
449 | #else
|
---|
450 | uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN;
|
---|
451 | memset(global_position_int_cov, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
---|
452 | memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), len);
|
---|
453 | #endif
|
---|
454 | }
|
---|