2 // MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING
4 #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48
7 typedef struct __mavlink_set_gps_global_origin_t
{
8 int32_t latitude
; /*< [degE7] Latitude (WGS84)*/
9 int32_t longitude
; /*< [degE7] Longitude (WGS84)*/
10 int32_t altitude
; /*< [mm] Altitude (MSL). Positive for up.*/
11 uint8_t target_system
; /*< System ID*/
12 uint64_t time_usec
; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
13 }) mavlink_set_gps_global_origin_t
;
15 #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 21
16 #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN 13
17 #define MAVLINK_MSG_ID_48_LEN 21
18 #define MAVLINK_MSG_ID_48_MIN_LEN 13
20 #define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41
21 #define MAVLINK_MSG_ID_48_CRC 41
25 #if MAVLINK_COMMAND_24BIT
26 #define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \
28 "SET_GPS_GLOBAL_ORIGIN", \
30 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \
31 { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \
32 { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \
33 { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \
34 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 13, offsetof(mavlink_set_gps_global_origin_t, time_usec) }, \
38 #define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \
39 "SET_GPS_GLOBAL_ORIGIN", \
41 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \
42 { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \
43 { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \
44 { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \
45 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 13, offsetof(mavlink_set_gps_global_origin_t, time_usec) }, \
51 * @brief Pack a set_gps_global_origin message
52 * @param system_id ID of this system
53 * @param component_id ID of this component (e.g. 200 for IMU)
54 * @param msg The MAVLink message to compress the data into
56 * @param target_system System ID
57 * @param latitude [degE7] Latitude (WGS84)
58 * @param longitude [degE7] Longitude (WGS84)
59 * @param altitude [mm] Altitude (MSL). Positive for up.
60 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
61 * @return length of the message in bytes (excluding serial stream start sign)
63 static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
64 uint8_t target_system
, int32_t latitude
, int32_t longitude
, int32_t altitude
, uint64_t time_usec
)
66 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf
[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
];
68 _mav_put_int32_t(buf
, 0, latitude
);
69 _mav_put_int32_t(buf
, 4, longitude
);
70 _mav_put_int32_t(buf
, 8, altitude
);
71 _mav_put_uint8_t(buf
, 12, target_system
);
72 _mav_put_uint64_t(buf
, 13, time_usec
);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
);
76 mavlink_set_gps_global_origin_t packet
;
77 packet
.latitude
= latitude
;
78 packet
.longitude
= longitude
;
79 packet
.altitude
= altitude
;
80 packet
.target_system
= target_system
;
81 packet
.time_usec
= time_usec
;
83 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
);
86 msg
->msgid
= MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN
;
87 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC
);
91 * @brief Pack a set_gps_global_origin message on a channel
92 * @param system_id ID of this system
93 * @param component_id ID of this component (e.g. 200 for IMU)
94 * @param chan The MAVLink channel this message will be sent over
95 * @param msg The MAVLink message to compress the data into
96 * @param target_system System ID
97 * @param latitude [degE7] Latitude (WGS84)
98 * @param longitude [degE7] Longitude (WGS84)
99 * @param altitude [mm] Altitude (MSL). Positive for up.
100 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
101 * @return length of the message in bytes (excluding serial stream start sign)
103 static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
104 mavlink_message_t
* msg
,
105 uint8_t target_system
,int32_t latitude
,int32_t longitude
,int32_t altitude
,uint64_t time_usec
)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 char buf
[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
];
109 _mav_put_int32_t(buf
, 0, latitude
);
110 _mav_put_int32_t(buf
, 4, longitude
);
111 _mav_put_int32_t(buf
, 8, altitude
);
112 _mav_put_uint8_t(buf
, 12, target_system
);
113 _mav_put_uint64_t(buf
, 13, time_usec
);
115 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
);
117 mavlink_set_gps_global_origin_t packet
;
118 packet
.latitude
= latitude
;
119 packet
.longitude
= longitude
;
120 packet
.altitude
= altitude
;
121 packet
.target_system
= target_system
;
122 packet
.time_usec
= time_usec
;
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
);
127 msg
->msgid
= MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN
;
128 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC
);
132 * @brief Encode a set_gps_global_origin struct
134 * @param system_id ID of this system
135 * @param component_id ID of this component (e.g. 200 for IMU)
136 * @param msg The MAVLink message to compress the data into
137 * @param set_gps_global_origin C-struct to read the message contents from
139 static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_set_gps_global_origin_t
* set_gps_global_origin
)
141 return mavlink_msg_set_gps_global_origin_pack(system_id
, component_id
, msg
, set_gps_global_origin
->target_system
, set_gps_global_origin
->latitude
, set_gps_global_origin
->longitude
, set_gps_global_origin
->altitude
, set_gps_global_origin
->time_usec
);
145 * @brief Encode a set_gps_global_origin struct on a channel
147 * @param system_id ID of this system
148 * @param component_id ID of this component (e.g. 200 for IMU)
149 * @param chan The MAVLink channel this message will be sent over
150 * @param msg The MAVLink message to compress the data into
151 * @param set_gps_global_origin C-struct to read the message contents from
153 static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_set_gps_global_origin_t
* set_gps_global_origin
)
155 return mavlink_msg_set_gps_global_origin_pack_chan(system_id
, component_id
, chan
, msg
, set_gps_global_origin
->target_system
, set_gps_global_origin
->latitude
, set_gps_global_origin
->longitude
, set_gps_global_origin
->altitude
, set_gps_global_origin
->time_usec
);
159 * @brief Send a set_gps_global_origin message
160 * @param chan MAVLink channel to send the message
162 * @param target_system System ID
163 * @param latitude [degE7] Latitude (WGS84)
164 * @param longitude [degE7] Longitude (WGS84)
165 * @param altitude [mm] Altitude (MSL). Positive for up.
166 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
168 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan
, uint8_t target_system
, int32_t latitude
, int32_t longitude
, int32_t altitude
, uint64_t time_usec
)
172 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
173 char buf
[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
];
174 _mav_put_int32_t(buf
, 0, latitude
);
175 _mav_put_int32_t(buf
, 4, longitude
);
176 _mav_put_int32_t(buf
, 8, altitude
);
177 _mav_put_uint8_t(buf
, 12, target_system
);
178 _mav_put_uint64_t(buf
, 13, time_usec
);
180 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN
, buf
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC
);
182 mavlink_set_gps_global_origin_t packet
;
183 packet
.latitude
= latitude
;
184 packet
.longitude
= longitude
;
185 packet
.altitude
= altitude
;
186 packet
.target_system
= target_system
;
187 packet
.time_usec
= time_usec
;
189 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN
, (const char *)&packet
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC
);
194 * @brief Send a set_gps_global_origin message
195 * @param chan MAVLink channel to send the message
196 * @param struct The MAVLink struct to serialize
198 static inline void mavlink_msg_set_gps_global_origin_send_struct(mavlink_channel_t chan
, const mavlink_set_gps_global_origin_t
* set_gps_global_origin
)
200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
201 mavlink_msg_set_gps_global_origin_send(chan
, set_gps_global_origin
->target_system
, set_gps_global_origin
->latitude
, set_gps_global_origin
->longitude
, set_gps_global_origin
->altitude
, set_gps_global_origin
->time_usec
);
203 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN
, (const char *)set_gps_global_origin
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC
);
207 #if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN
209 This varient of _send() can be used to save stack space by re-using
210 memory from the receive buffer. The caller provides a
211 mavlink_message_t which is the size of a full mavlink message. This
212 is usually the receive buffer for the channel, and allows a reply to an
213 incoming message with minimum stack space usage.
215 static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint8_t target_system
, int32_t latitude
, int32_t longitude
, int32_t altitude
, uint64_t time_usec
)
217 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
218 char *buf
= (char *)msgbuf
;
219 _mav_put_int32_t(buf
, 0, latitude
);
220 _mav_put_int32_t(buf
, 4, longitude
);
221 _mav_put_int32_t(buf
, 8, altitude
);
222 _mav_put_uint8_t(buf
, 12, target_system
);
223 _mav_put_uint64_t(buf
, 13, time_usec
);
225 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN
, buf
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC
);
227 mavlink_set_gps_global_origin_t
*packet
= (mavlink_set_gps_global_origin_t
*)msgbuf
;
228 packet
->latitude
= latitude
;
229 packet
->longitude
= longitude
;
230 packet
->altitude
= altitude
;
231 packet
->target_system
= target_system
;
232 packet
->time_usec
= time_usec
;
234 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN
, (const char *)packet
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC
);
241 // MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING
245 * @brief Get field target_system from set_gps_global_origin message
249 static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t
* msg
)
251 return _MAV_RETURN_uint8_t(msg
, 12);
255 * @brief Get field latitude from set_gps_global_origin message
257 * @return [degE7] Latitude (WGS84)
259 static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t
* msg
)
261 return _MAV_RETURN_int32_t(msg
, 0);
265 * @brief Get field longitude from set_gps_global_origin message
267 * @return [degE7] Longitude (WGS84)
269 static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t
* msg
)
271 return _MAV_RETURN_int32_t(msg
, 4);
275 * @brief Get field altitude from set_gps_global_origin message
277 * @return [mm] Altitude (MSL). Positive for up.
279 static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t
* msg
)
281 return _MAV_RETURN_int32_t(msg
, 8);
285 * @brief Get field time_usec from set_gps_global_origin message
287 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
289 static inline uint64_t mavlink_msg_set_gps_global_origin_get_time_usec(const mavlink_message_t
* msg
)
291 return _MAV_RETURN_uint64_t(msg
, 13);
295 * @brief Decode a set_gps_global_origin message into a struct
297 * @param msg The message to decode
298 * @param set_gps_global_origin C-struct to decode the message contents into
300 static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t
* msg
, mavlink_set_gps_global_origin_t
* set_gps_global_origin
)
302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
303 set_gps_global_origin
->latitude
= mavlink_msg_set_gps_global_origin_get_latitude(msg
);
304 set_gps_global_origin
->longitude
= mavlink_msg_set_gps_global_origin_get_longitude(msg
);
305 set_gps_global_origin
->altitude
= mavlink_msg_set_gps_global_origin_get_altitude(msg
);
306 set_gps_global_origin
->target_system
= mavlink_msg_set_gps_global_origin_get_target_system(msg
);
307 set_gps_global_origin
->time_usec
= mavlink_msg_set_gps_global_origin_get_time_usec(msg
);
309 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
? msg
->len
: MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
;
310 memset(set_gps_global_origin
, 0, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN
);
311 memcpy(set_gps_global_origin
, _MAV_PAYLOAD(msg
), len
);