mavlink_msg_global_position_setpoint_int.h 9.32 KB
Newer Older
1 2 3 4
// MESSAGE GLOBAL_POSITION_SETPOINT_INT PACKING

#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52

lm's avatar
lm committed
5
typedef struct __mavlink_global_position_setpoint_int_t
6
{
lm's avatar
lm committed
7 8 9 10
 int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7
 int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7
 int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up)
 int16_t yaw; ///< Desired yaw angle in degrees * 100
lm's avatar
lm committed
11
 uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
12 13
} mavlink_global_position_setpoint_int_t;

lm's avatar
lm committed
14 15
#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15
#define MAVLINK_MSG_ID_52_LEN 15
lm's avatar
lm committed
16 17 18 19 20



#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT { \
	"GLOBAL_POSITION_SETPOINT_INT", \
lm's avatar
lm committed
21 22 23 24 25 26
	5, \
	{  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \
         { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \
         { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \
         { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \
         { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_global_position_setpoint_int_t, coordinate_frame) }, \
lm's avatar
lm committed
27 28 29 30
         } \
}


31 32 33 34 35 36
/**
 * @brief Pack a global_position_setpoint_int 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_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
38 39 40 41 42 43
 * @param latitude WGS84 Latitude position in degrees * 1E7
 * @param longitude WGS84 Longitude position in degrees * 1E7
 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
 * @param yaw Desired yaw angle in degrees * 100
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
44
static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
lm's avatar
lm committed
45
						       uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
46
{
LM's avatar
LM committed
47
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
48
	char buf[15];
LM's avatar
LM committed
49 50 51 52
	_mav_put_int32_t(buf, 0, latitude);
	_mav_put_int32_t(buf, 4, longitude);
	_mav_put_int32_t(buf, 8, altitude);
	_mav_put_int16_t(buf, 12, yaw);
lm's avatar
lm committed
53
	_mav_put_uint8_t(buf, 14, coordinate_frame);
LM's avatar
LM committed
54

55
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
LM's avatar
LM committed
56 57 58 59 60 61
#else
	mavlink_global_position_setpoint_int_t packet;
	packet.latitude = latitude;
	packet.longitude = longitude;
	packet.altitude = altitude;
	packet.yaw = yaw;
lm's avatar
lm committed
62
	packet.coordinate_frame = coordinate_frame;
63

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

LM's avatar
LM committed
67
	msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
lm's avatar
lm committed
68
	return mavlink_finalize_message(msg, system_id, component_id, 15, 141);
69 70 71
}

/**
lm's avatar
lm committed
72
 * @brief Pack a global_position_setpoint_int message on a channel
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_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
78 79 80 81 82 83
 * @param latitude WGS84 Latitude position in degrees * 1E7
 * @param longitude WGS84 Longitude position in degrees * 1E7
 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
 * @param yaw Desired yaw angle in degrees * 100
 * @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_global_position_setpoint_int_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,int32_t latitude,int32_t longitude,int32_t altitude,int16_t 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[15];
LM's avatar
LM committed
90 91 92 93
	_mav_put_int32_t(buf, 0, latitude);
	_mav_put_int32_t(buf, 4, longitude);
	_mav_put_int32_t(buf, 8, altitude);
	_mav_put_int16_t(buf, 12, yaw);
lm's avatar
lm committed
94
	_mav_put_uint8_t(buf, 14, coordinate_frame);
LM's avatar
LM committed
95

96
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
LM's avatar
LM committed
97 98 99 100 101 102
#else
	mavlink_global_position_setpoint_int_t packet;
	packet.latitude = latitude;
	packet.longitude = longitude;
	packet.altitude = altitude;
	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, 15);
LM's avatar
LM committed
106
#endif
lm's avatar
lm committed
107

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

112 113 114 115 116 117 118 119 120 121
/**
 * @brief Encode a global_position_setpoint_int 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 global_position_setpoint_int C-struct to read the message contents from
 */
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)
{
lm's avatar
lm committed
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);
123 124 125 126 127 128
}

/**
 * @brief Send a global_position_setpoint_int 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_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
130 131 132 133 134
 * @param latitude WGS84 Latitude position in degrees * 1E7
 * @param longitude WGS84 Longitude position in degrees * 1E7
 * @param altitude WGS84 Altitude in meters * 1000 (positive for up)
 * @param yaw Desired yaw angle in degrees * 100
 */
lm's avatar
lm committed
135 136
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
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)
138
{
LM's avatar
LM committed
139
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
140
	char buf[15];
LM's avatar
LM committed
141 142 143 144
	_mav_put_int32_t(buf, 0, latitude);
	_mav_put_int32_t(buf, 4, longitude);
	_mav_put_int32_t(buf, 8, altitude);
	_mav_put_int16_t(buf, 12, yaw);
lm's avatar
lm committed
145
	_mav_put_uint8_t(buf, 14, coordinate_frame);
LM's avatar
LM committed
146

lm's avatar
lm committed
147
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 141);
LM's avatar
LM committed
148 149 150 151 152 153
#else
	mavlink_global_position_setpoint_int_t packet;
	packet.latitude = latitude;
	packet.longitude = longitude;
	packet.altitude = altitude;
	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_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 141);
LM's avatar
LM committed
157
#endif
158 159 160
}

#endif
lm's avatar
lm committed
161

162 163
// MESSAGE GLOBAL_POSITION_SETPOINT_INT 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 global_position_setpoint_int message
 *
 * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
 */
static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg)
{
	return _MAV_RETURN_uint8_t(msg,  14);
}

175 176 177 178 179 180 181
/**
 * @brief Get field latitude from global_position_setpoint_int message
 *
 * @return WGS84 Latitude position in degrees * 1E7
 */
static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg)
{
LM's avatar
LM committed
182
	return _MAV_RETURN_int32_t(msg,  0);
183 184 185 186 187 188 189 190 191
}

/**
 * @brief Get field longitude from global_position_setpoint_int message
 *
 * @return WGS84 Longitude position in degrees * 1E7
 */
static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg)
{
LM's avatar
LM committed
192
	return _MAV_RETURN_int32_t(msg,  4);
193 194 195 196 197 198 199 200 201
}

/**
 * @brief Get field altitude from global_position_setpoint_int message
 *
 * @return WGS84 Altitude in meters * 1000 (positive for up)
 */
static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg)
{
LM's avatar
LM committed
202
	return _MAV_RETURN_int32_t(msg,  8);
203 204 205 206 207 208 209 210 211
}

/**
 * @brief Get field yaw from global_position_setpoint_int message
 *
 * @return Desired yaw angle in degrees * 100
 */
static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg)
{
LM's avatar
LM committed
212
	return _MAV_RETURN_int16_t(msg,  12);
213 214 215 216 217 218 219 220 221 222
}

/**
 * @brief Decode a global_position_setpoint_int message into a struct
 *
 * @param msg The message to decode
 * @param global_position_setpoint_int C-struct to decode the message contents into
 */
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)
{
lm's avatar
lm committed
223 224 225 226 227
#if MAVLINK_NEED_BYTE_SWAP
	global_position_setpoint_int->latitude = mavlink_msg_global_position_setpoint_int_get_latitude(msg);
	global_position_setpoint_int->longitude = mavlink_msg_global_position_setpoint_int_get_longitude(msg);
	global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg);
	global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg);
lm's avatar
lm committed
228
	global_position_setpoint_int->coordinate_frame = mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg);
lm's avatar
lm committed
229
#else
lm's avatar
lm committed
230
	memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 15);
lm's avatar
lm committed
231
#endif
232
}