1 // MESSAGE LOCAL_POSITION_SETPOINT PACKING
3 #define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51
5 typedef struct __mavlink_local_position_setpoint_t
{
6 float x
; ///< x position
7 float y
; ///< y position
8 float z
; ///< z position
9 float yaw
; ///< Desired yaw angle
10 uint8_t coordinate_frame
; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
11 } mavlink_local_position_setpoint_t
;
13 #define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17
14 #define MAVLINK_MSG_ID_51_LEN 17
17 #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT \
19 "LOCAL_POSITION_SETPOINT", \
22 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \
23 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \
24 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \
25 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \
26 { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_local_position_setpoint_t, coordinate_frame) }, \
32 * @brief Pack a local_position_setpoint 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_LOCAL_NED or MAV_FRAME_LOCAL_ENU
41 * @param yaw Desired yaw angle
42 * @return length of the message in bytes (excluding serial stream start sign)
44 static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
45 uint8_t coordinate_frame
, float x
, float y
, float z
, float yaw
)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
49 _mav_put_float(buf
, 0, x
);
50 _mav_put_float(buf
, 4, y
);
51 _mav_put_float(buf
, 8, z
);
52 _mav_put_float(buf
, 12, yaw
);
53 _mav_put_uint8_t(buf
, 16, coordinate_frame
);
55 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 17);
57 mavlink_local_position_setpoint_t packet
;
62 packet
.coordinate_frame
= coordinate_frame
;
64 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 17);
67 msg
->msgid
= MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT
;
68 return mavlink_finalize_message(msg
, system_id
, component_id
, 17, 223);
72 * @brief Pack a local_position_setpoint 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_LOCAL_NED or MAV_FRAME_LOCAL_ENU
81 * @param yaw Desired yaw angle
82 * @return length of the message in bytes (excluding serial stream start sign)
84 static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
85 mavlink_message_t
*msg
,
86 uint8_t coordinate_frame
, float x
, float y
, float z
, float yaw
)
88 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
90 _mav_put_float(buf
, 0, x
);
91 _mav_put_float(buf
, 4, y
);
92 _mav_put_float(buf
, 8, z
);
93 _mav_put_float(buf
, 12, yaw
);
94 _mav_put_uint8_t(buf
, 16, coordinate_frame
);
96 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 17);
98 mavlink_local_position_setpoint_t packet
;
103 packet
.coordinate_frame
= coordinate_frame
;
105 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 17);
108 msg
->msgid
= MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT
;
109 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 17, 223);
113 * @brief Encode a local_position_setpoint 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 local_position_setpoint C-struct to read the message contents from
120 static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
, const mavlink_local_position_setpoint_t
*local_position_setpoint
)
122 return mavlink_msg_local_position_setpoint_pack(system_id
, component_id
, msg
, local_position_setpoint
->coordinate_frame
, local_position_setpoint
->x
, local_position_setpoint
->y
, local_position_setpoint
->z
, local_position_setpoint
->yaw
);
126 * @brief Send a local_position_setpoint message
127 * @param chan MAVLink channel to send the message
129 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
130 * @param x x position
131 * @param y y position
132 * @param z z position
133 * @param yaw Desired yaw angle
135 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
137 static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan
, uint8_t coordinate_frame
, float x
, float y
, float z
, float yaw
)
139 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
141 _mav_put_float(buf
, 0, x
);
142 _mav_put_float(buf
, 4, y
);
143 _mav_put_float(buf
, 8, z
);
144 _mav_put_float(buf
, 12, yaw
);
145 _mav_put_uint8_t(buf
, 16, coordinate_frame
);
147 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT
, buf
, 17, 223);
149 mavlink_local_position_setpoint_t packet
;
154 packet
.coordinate_frame
= coordinate_frame
;
156 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT
, (const char *)&packet
, 17, 223);
160 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
162 // MESSAGE LOCAL_POSITION_SETPOINT UNPACKING
166 * @brief Get field coordinate_frame from local_position_setpoint message
168 * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
170 static inline uint8_t mavlink_msg_local_position_setpoint_get_coordinate_frame(const mavlink_message_t
*msg
)
172 return _MAV_RETURN_uint8_t(msg
, 16);
176 * @brief Get field x from local_position_setpoint message
180 static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t
*msg
)
182 return _MAV_RETURN_float(msg
, 0);
186 * @brief Get field y from local_position_setpoint message
190 static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t
*msg
)
192 return _MAV_RETURN_float(msg
, 4);
196 * @brief Get field z from local_position_setpoint message
200 static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t
*msg
)
202 return _MAV_RETURN_float(msg
, 8);
206 * @brief Get field yaw from local_position_setpoint message
208 * @return Desired yaw angle
210 static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t
*msg
)
212 return _MAV_RETURN_float(msg
, 12);
216 * @brief Decode a local_position_setpoint message into a struct
218 * @param msg The message to decode
219 * @param local_position_setpoint C-struct to decode the message contents into
221 static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t
*msg
, mavlink_local_position_setpoint_t
*local_position_setpoint
)
223 #if MAVLINK_NEED_BYTE_SWAP
224 local_position_setpoint
->x
= mavlink_msg_local_position_setpoint_get_x(msg
);
225 local_position_setpoint
->y
= mavlink_msg_local_position_setpoint_get_y(msg
);
226 local_position_setpoint
->z
= mavlink_msg_local_position_setpoint_get_z(msg
);
227 local_position_setpoint
->yaw
= mavlink_msg_local_position_setpoint_get_yaw(msg
);
228 local_position_setpoint
->coordinate_frame
= mavlink_msg_local_position_setpoint_get_coordinate_frame(msg
);
230 memcpy(local_position_setpoint
, _MAV_PAYLOAD(msg
), 17);