mavlink_msg_local_position_setpoint.h 7.83 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE LOCAL_POSITION_SETPOINT PACKING

#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51

lm's avatar
lm committed
5
typedef struct __mavlink_local_position_setpoint_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10
 float x; ///< x position
 float y; ///< y position
 float z; ///< z position
 float yaw; ///< Desired yaw angle
lm's avatar
lm committed
11
 uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
James Goppert's avatar
James Goppert committed
12 13
} mavlink_local_position_setpoint_t;

lm's avatar
lm committed
14 15
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17
#define MAVLINK_MSG_ID_51_LEN 17
lm's avatar
lm committed
16 17 18 19 20



#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \
	"LOCAL_POSITION_SETPOINT", \
lm's avatar
lm committed
21 22 23 24 25 26
	5, \
	{  { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \
         { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \
         { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \
         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \
         { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_local_position_setpoint_t, coordinate_frame) }, \
lm's avatar
lm committed
27 28 29 30
         } \
}


James Goppert's avatar
James Goppert committed
31 32 33 34 35 36
/**
 * @brief Pack a local_position_setpoint message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
lm's avatar
lm committed
37
 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
James Goppert's avatar
James Goppert committed
38 39 40 41 42 43
 * @param x x position
 * @param y y position
 * @param z z position
 * @param yaw Desired yaw angle
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
44
static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
lm's avatar
lm committed
45
						       uint8_t coordinate_frame, float x, float y, float z, float yaw)
James Goppert's avatar
James Goppert committed
46
{
LM's avatar
LM committed
47
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
48
	char buf[17];
LM's avatar
LM committed
49 50 51 52
	_mav_put_float(buf, 0, x);
	_mav_put_float(buf, 4, y);
	_mav_put_float(buf, 8, z);
	_mav_put_float(buf, 12, yaw);
lm's avatar
lm committed
53
	_mav_put_uint8_t(buf, 16, coordinate_frame);
LM's avatar
LM committed
54

55
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
LM's avatar
LM committed
56 57 58 59 60 61
#else
	mavlink_local_position_setpoint_t packet;
	packet.x = x;
	packet.y = y;
	packet.z = z;
	packet.yaw = yaw;
lm's avatar
lm committed
62
	packet.coordinate_frame = coordinate_frame;
James Goppert's avatar
James Goppert committed
63

64
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
LM's avatar
LM committed
65
#endif
James Goppert's avatar
James Goppert committed
66

LM's avatar
LM committed
67
	msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
lm's avatar
lm committed
68
	return mavlink_finalize_message(msg, system_id, component_id, 17, 223);
James Goppert's avatar
James Goppert committed
69 70 71
}

/**
lm's avatar
lm committed
72
 * @brief Pack a local_position_setpoint message on a channel
James Goppert's avatar
James Goppert committed
73 74 75 76
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
lm's avatar
lm committed
77
 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
James Goppert's avatar
James Goppert committed
78 79 80 81 82 83
 * @param x x position
 * @param y y position
 * @param z z position
 * @param yaw Desired yaw angle
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
84 85
static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
lm's avatar
lm committed
86
						           uint8_t coordinate_frame,float x,float y,float z,float yaw)
lm's avatar
lm committed
87
{
LM's avatar
LM committed
88
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
89
	char buf[17];
LM's avatar
LM committed
90 91 92 93
	_mav_put_float(buf, 0, x);
	_mav_put_float(buf, 4, y);
	_mav_put_float(buf, 8, z);
	_mav_put_float(buf, 12, yaw);
lm's avatar
lm committed
94
	_mav_put_uint8_t(buf, 16, coordinate_frame);
LM's avatar
LM committed
95

96
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
LM's avatar
LM committed
97 98 99 100 101 102
#else
	mavlink_local_position_setpoint_t packet;
	packet.x = x;
	packet.y = y;
	packet.z = z;
	packet.yaw = yaw;
lm's avatar
lm committed
103
	packet.coordinate_frame = coordinate_frame;
lm's avatar
lm committed
104

105
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
LM's avatar
LM committed
106
#endif
lm's avatar
lm committed
107

LM's avatar
LM committed
108
	msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
lm's avatar
lm committed
109
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 223);
lm's avatar
lm committed
110 111
}

James Goppert's avatar
James Goppert committed
112 113 114 115 116 117 118 119 120 121
/**
 * @brief Encode a local_position_setpoint struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param local_position_setpoint C-struct to read the message contents from
 */
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)
{
lm's avatar
lm committed
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);
James Goppert's avatar
James Goppert committed
123 124 125 126 127 128
}

/**
 * @brief Send a local_position_setpoint message
 * @param chan MAVLink channel to send the message
 *
lm's avatar
lm committed
129
 * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
James Goppert's avatar
James Goppert committed
130 131 132 133 134
 * @param x x position
 * @param y y position
 * @param z z position
 * @param yaw Desired yaw angle
 */
lm's avatar
lm committed
135 136
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
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)
lm's avatar
lm committed
138
{
LM's avatar
LM committed
139
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
140
	char buf[17];
LM's avatar
LM committed
141 142 143 144
	_mav_put_float(buf, 0, x);
	_mav_put_float(buf, 4, y);
	_mav_put_float(buf, 8, z);
	_mav_put_float(buf, 12, yaw);
lm's avatar
lm committed
145
	_mav_put_uint8_t(buf, 16, coordinate_frame);
LM's avatar
LM committed
146

lm's avatar
lm committed
147
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 17, 223);
LM's avatar
LM committed
148 149 150 151 152 153
#else
	mavlink_local_position_setpoint_t packet;
	packet.x = x;
	packet.y = y;
	packet.z = z;
	packet.yaw = yaw;
lm's avatar
lm committed
154
	packet.coordinate_frame = coordinate_frame;
LM's avatar
LM committed
155

lm's avatar
lm committed
156
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 17, 223);
LM's avatar
LM committed
157
#endif
James Goppert's avatar
James Goppert committed
158 159 160
}

#endif
lm's avatar
lm committed
161

James Goppert's avatar
James Goppert committed
162 163
// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING

lm's avatar
lm committed
164

lm's avatar
lm committed
165 166 167 168 169 170 171 172 173 174
/**
 * @brief Get field coordinate_frame from local_position_setpoint message
 *
 * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
 */
static inline uint8_t mavlink_msg_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg)
{
	return _MAV_RETURN_uint8_t(msg,  16);
}

James Goppert's avatar
James Goppert committed
175 176 177 178 179 180 181
/**
 * @brief Get field x from local_position_setpoint message
 *
 * @return x position
 */
static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg)
{
LM's avatar
LM committed
182
	return _MAV_RETURN_float(msg,  0);
James Goppert's avatar
James Goppert committed
183 184 185 186 187 188 189 190 191
}

/**
 * @brief Get field y from local_position_setpoint message
 *
 * @return y position
 */
static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg)
{
LM's avatar
LM committed
192
	return _MAV_RETURN_float(msg,  4);
James Goppert's avatar
James Goppert committed
193 194 195 196 197 198 199 200 201
}

/**
 * @brief Get field z from local_position_setpoint message
 *
 * @return z position
 */
static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg)
{
LM's avatar
LM committed
202
	return _MAV_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
203 204 205 206 207 208 209 210 211
}

/**
 * @brief Get field yaw from local_position_setpoint message
 *
 * @return Desired yaw angle
 */
static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg)
{
LM's avatar
LM committed
212
	return _MAV_RETURN_float(msg,  12);
James Goppert's avatar
James Goppert committed
213 214 215 216 217 218 219 220 221 222
}

/**
 * @brief Decode a local_position_setpoint message into a struct
 *
 * @param msg The message to decode
 * @param local_position_setpoint C-struct to decode the message contents into
 */
static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint)
{
lm's avatar
lm committed
223 224 225 226 227
#if MAVLINK_NEED_BYTE_SWAP
	local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg);
	local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg);
	local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg);
	local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg);
lm's avatar
lm committed
228
	local_position_setpoint->coordinate_frame = mavlink_msg_local_position_setpoint_get_coordinate_frame(msg);
lm's avatar
lm committed
229
#else
lm's avatar
lm committed
230
	memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 17);
lm's avatar
lm committed
231
#endif
James Goppert's avatar
James Goppert committed
232
}