1 // MESSAGE GLOBAL_POSITION_SETPOINT_INT PACKING
3 #define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52
5 typedef struct __mavlink_global_position_setpoint_int_t
{
6 int32_t latitude
; ///< WGS84 Latitude position in degrees * 1E7
7 int32_t longitude
; ///< WGS84 Longitude position in degrees * 1E7
8 int32_t altitude
; ///< WGS84 Altitude in meters * 1000 (positive for up)
9 int16_t yaw
; ///< Desired yaw angle in degrees * 100
10 uint8_t coordinate_frame
; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
11 } mavlink_global_position_setpoint_int_t
;
13 #define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15
14 #define MAVLINK_MSG_ID_52_LEN 15
17 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT \
19 "GLOBAL_POSITION_SETPOINT_INT", \
22 { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \
23 { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \
24 { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \
25 { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \
26 { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_global_position_setpoint_int_t, coordinate_frame) }, \
32 * @brief Pack a global_position_setpoint_int message
33 * @param system_id ID of this system
34 * @param component_id ID of this component (e.g. 200 for IMU)
35 * @param msg The MAVLink message to compress the data into
37 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
38 * @param latitude WGS84 Latitude position in degrees * 1E7
39 * @param longitude WGS84 Longitude position in degrees * 1E7
40 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
41 * @param yaw Desired yaw angle in degrees * 100
42 * @return length of the message in bytes (excluding serial stream start sign)
44 static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
45 uint8_t coordinate_frame
, int32_t latitude
, int32_t longitude
, int32_t altitude
, int16_t yaw
)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
49 _mav_put_int32_t(buf
, 0, latitude
);
50 _mav_put_int32_t(buf
, 4, longitude
);
51 _mav_put_int32_t(buf
, 8, altitude
);
52 _mav_put_int16_t(buf
, 12, yaw
);
53 _mav_put_uint8_t(buf
, 14, coordinate_frame
);
55 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 15);
57 mavlink_global_position_setpoint_int_t packet
;
58 packet
.latitude
= latitude
;
59 packet
.longitude
= longitude
;
60 packet
.altitude
= altitude
;
62 packet
.coordinate_frame
= coordinate_frame
;
64 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 15);
67 msg
->msgid
= MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT
;
68 return mavlink_finalize_message(msg
, system_id
, component_id
, 15, 141);
72 * @brief Pack a global_position_setpoint_int message on a channel
73 * @param system_id ID of this system
74 * @param component_id ID of this component (e.g. 200 for IMU)
75 * @param chan The MAVLink channel this message was sent over
76 * @param msg The MAVLink message to compress the data into
77 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
78 * @param latitude WGS84 Latitude position in degrees * 1E7
79 * @param longitude WGS84 Longitude position in degrees * 1E7
80 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
81 * @param yaw Desired yaw angle in degrees * 100
82 * @return length of the message in bytes (excluding serial stream start sign)
84 static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
85 mavlink_message_t
*msg
,
86 uint8_t coordinate_frame
, int32_t latitude
, int32_t longitude
, int32_t altitude
, int16_t yaw
)
88 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
90 _mav_put_int32_t(buf
, 0, latitude
);
91 _mav_put_int32_t(buf
, 4, longitude
);
92 _mav_put_int32_t(buf
, 8, altitude
);
93 _mav_put_int16_t(buf
, 12, yaw
);
94 _mav_put_uint8_t(buf
, 14, coordinate_frame
);
96 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 15);
98 mavlink_global_position_setpoint_int_t packet
;
99 packet
.latitude
= latitude
;
100 packet
.longitude
= longitude
;
101 packet
.altitude
= altitude
;
103 packet
.coordinate_frame
= coordinate_frame
;
105 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 15);
108 msg
->msgid
= MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT
;
109 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 15, 141);
113 * @brief Encode a global_position_setpoint_int struct into a message
115 * @param system_id ID of this system
116 * @param component_id ID of this component (e.g. 200 for IMU)
117 * @param msg The MAVLink message to compress the data into
118 * @param global_position_setpoint_int C-struct to read the message contents from
120 static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
, const mavlink_global_position_setpoint_int_t
*global_position_setpoint_int
)
122 return mavlink_msg_global_position_setpoint_int_pack(system_id
, component_id
, msg
, global_position_setpoint_int
->coordinate_frame
, global_position_setpoint_int
->latitude
, global_position_setpoint_int
->longitude
, global_position_setpoint_int
->altitude
, global_position_setpoint_int
->yaw
);
126 * @brief Send a global_position_setpoint_int message
127 * @param chan MAVLink channel to send the message
129 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
130 * @param latitude WGS84 Latitude position in degrees * 1E7
131 * @param longitude WGS84 Longitude position in degrees * 1E7
132 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
133 * @param yaw Desired yaw angle in degrees * 100
135 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
137 static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan
, uint8_t coordinate_frame
, int32_t latitude
, int32_t longitude
, int32_t altitude
, int16_t yaw
)
139 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
141 _mav_put_int32_t(buf
, 0, latitude
);
142 _mav_put_int32_t(buf
, 4, longitude
);
143 _mav_put_int32_t(buf
, 8, altitude
);
144 _mav_put_int16_t(buf
, 12, yaw
);
145 _mav_put_uint8_t(buf
, 14, coordinate_frame
);
147 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT
, buf
, 15, 141);
149 mavlink_global_position_setpoint_int_t packet
;
150 packet
.latitude
= latitude
;
151 packet
.longitude
= longitude
;
152 packet
.altitude
= altitude
;
154 packet
.coordinate_frame
= coordinate_frame
;
156 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT
, (const char *)&packet
, 15, 141);
160 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
162 // MESSAGE GLOBAL_POSITION_SETPOINT_INT UNPACKING
166 * @brief Get field coordinate_frame from global_position_setpoint_int message
168 * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
170 static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t
*msg
)
172 return _MAV_RETURN_uint8_t(msg
, 14);
176 * @brief Get field latitude from global_position_setpoint_int message
178 * @return WGS84 Latitude position in degrees * 1E7
180 static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t
*msg
)
182 return _MAV_RETURN_int32_t(msg
, 0);
186 * @brief Get field longitude from global_position_setpoint_int message
188 * @return WGS84 Longitude position in degrees * 1E7
190 static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t
*msg
)
192 return _MAV_RETURN_int32_t(msg
, 4);
196 * @brief Get field altitude from global_position_setpoint_int message
198 * @return WGS84 Altitude in meters * 1000 (positive for up)
200 static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t
*msg
)
202 return _MAV_RETURN_int32_t(msg
, 8);
206 * @brief Get field yaw from global_position_setpoint_int message
208 * @return Desired yaw angle in degrees * 100
210 static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t
*msg
)
212 return _MAV_RETURN_int16_t(msg
, 12);
216 * @brief Decode a global_position_setpoint_int message into a struct
218 * @param msg The message to decode
219 * @param global_position_setpoint_int C-struct to decode the message contents into
221 static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink_message_t
*msg
, mavlink_global_position_setpoint_int_t
*global_position_setpoint_int
)
223 #if MAVLINK_NEED_BYTE_SWAP
224 global_position_setpoint_int
->latitude
= mavlink_msg_global_position_setpoint_int_get_latitude(msg
);
225 global_position_setpoint_int
->longitude
= mavlink_msg_global_position_setpoint_int_get_longitude(msg
);
226 global_position_setpoint_int
->altitude
= mavlink_msg_global_position_setpoint_int_get_altitude(msg
);
227 global_position_setpoint_int
->yaw
= mavlink_msg_global_position_setpoint_int_get_yaw(msg
);
228 global_position_setpoint_int
->coordinate_frame
= mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg
);
230 memcpy(global_position_setpoint_int
, _MAV_PAYLOAD(msg
), 15);