mavlink_msg_marker.h 7.62 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE MARKER PACKING

lm's avatar
lm committed
3
#define MAVLINK_MSG_ID_MARKER 171
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_marker_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11 12 13
 float x; ///< x position
 float y; ///< y position
 float z; ///< z position
 float roll; ///< roll orientation
 float pitch; ///< pitch orientation
 float yaw; ///< yaw orientation
 uint16_t id; ///< ID
James Goppert's avatar
James Goppert committed
14 15
} mavlink_marker_t;

lm's avatar
lm committed
16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34
#define MAVLINK_MSG_ID_MARKER_LEN 26
#define MAVLINK_MSG_ID_171_LEN 26



#define MAVLINK_MESSAGE_INFO_MARKER { \
	"MARKER", \
	7, \
	{  { "x", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_marker_t, x) }, \
         { "y", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_marker_t, y) }, \
         { "z", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_marker_t, z) }, \
         { "roll", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_marker_t, roll) }, \
         { "pitch", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_marker_t, pitch) }, \
         { "yaw", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_marker_t, yaw) }, \
         { "id", MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_marker_t, id) }, \
         } \
}


James Goppert's avatar
James Goppert committed
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49
/**
 * @brief Pack a marker 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 id ID
 * @param x x position
 * @param y y position
 * @param z z position
 * @param roll roll orientation
 * @param pitch pitch orientation
 * @param yaw yaw orientation
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
50 51
static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
James Goppert's avatar
James Goppert committed
52 53 54
{
	msg->msgid = MAVLINK_MSG_ID_MARKER;

lm's avatar
lm committed
55 56 57 58 59 60 61
	put_float_by_index(msg, 0, x); // x position
	put_float_by_index(msg, 4, y); // y position
	put_float_by_index(msg, 8, z); // z position
	put_float_by_index(msg, 12, roll); // roll orientation
	put_float_by_index(msg, 16, pitch); // pitch orientation
	put_float_by_index(msg, 20, yaw); // yaw orientation
	put_uint16_t_by_index(msg, 24, id); // ID
James Goppert's avatar
James Goppert committed
62

lm's avatar
lm committed
63
	return mavlink_finalize_message(msg, system_id, component_id, 26, 249);
James Goppert's avatar
James Goppert committed
64 65 66
}

/**
lm's avatar
lm committed
67
 * @brief Pack a marker message on a channel
James Goppert's avatar
James Goppert committed
68 69 70 71 72 73 74 75 76 77 78 79 80
 * @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
 * @param id ID
 * @param x x position
 * @param y y position
 * @param z z position
 * @param roll roll orientation
 * @param pitch pitch orientation
 * @param yaw yaw orientation
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
81 82 83
static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint16_t id,float x,float y,float z,float roll,float pitch,float yaw)
James Goppert's avatar
James Goppert committed
84 85 86
{
	msg->msgid = MAVLINK_MSG_ID_MARKER;

lm's avatar
lm committed
87 88 89 90 91 92 93
	put_float_by_index(msg, 0, x); // x position
	put_float_by_index(msg, 4, y); // y position
	put_float_by_index(msg, 8, z); // z position
	put_float_by_index(msg, 12, roll); // roll orientation
	put_float_by_index(msg, 16, pitch); // pitch orientation
	put_float_by_index(msg, 20, yaw); // yaw orientation
	put_uint16_t_by_index(msg, 24, id); // ID
James Goppert's avatar
James Goppert committed
94

lm's avatar
lm committed
95
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 249);
James Goppert's avatar
James Goppert committed
96 97
}

lm's avatar
lm committed
98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

/**
 * @brief Pack a marker message on a channel and send
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param id ID
 * @param x x position
 * @param y y position
 * @param z z position
 * @param roll roll orientation
 * @param pitch pitch orientation
 * @param yaw yaw orientation
 */
static inline void mavlink_msg_marker_pack_chan_send(mavlink_channel_t chan,
							   mavlink_message_t* msg,
						           uint16_t id,float x,float y,float z,float roll,float pitch,float yaw)
{
	msg->msgid = MAVLINK_MSG_ID_MARKER;

	put_float_by_index(msg, 0, x); // x position
	put_float_by_index(msg, 4, y); // y position
	put_float_by_index(msg, 8, z); // z position
	put_float_by_index(msg, 12, roll); // roll orientation
	put_float_by_index(msg, 16, pitch); // pitch orientation
	put_float_by_index(msg, 20, yaw); // yaw orientation
	put_uint16_t_by_index(msg, 24, id); // ID

	mavlink_finalize_message_chan_send(msg, chan, 26, 249);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS


James Goppert's avatar
James Goppert committed
131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155
/**
 * @brief Encode a marker 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 marker C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker)
{
	return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
}

/**
 * @brief Send a marker message
 * @param chan MAVLink channel to send the message
 *
 * @param id ID
 * @param x x position
 * @param y y position
 * @param z z position
 * @param roll roll orientation
 * @param pitch pitch orientation
 * @param yaw yaw orientation
 */
lm's avatar
lm committed
156 157
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
158 159
static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
{
lm's avatar
lm committed
160 161
	MAVLINK_ALIGNED_MESSAGE(msg, 26);
	mavlink_msg_marker_pack_chan_send(chan, msg, id, x, y, z, roll, pitch, yaw);
James Goppert's avatar
James Goppert committed
162 163 164
}

#endif
lm's avatar
lm committed
165

James Goppert's avatar
James Goppert committed
166 167
// MESSAGE MARKER UNPACKING

lm's avatar
lm committed
168

James Goppert's avatar
James Goppert committed
169 170 171 172 173 174 175
/**
 * @brief Get field id from marker message
 *
 * @return ID
 */
static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg)
{
lm's avatar
lm committed
176
	return MAVLINK_MSG_RETURN_uint16_t(msg,  24);
James Goppert's avatar
James Goppert committed
177 178 179 180 181 182 183 184 185
}

/**
 * @brief Get field x from marker message
 *
 * @return x position
 */
static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg)
{
lm's avatar
lm committed
186
	return MAVLINK_MSG_RETURN_float(msg,  0);
James Goppert's avatar
James Goppert committed
187 188 189 190 191 192 193 194 195
}

/**
 * @brief Get field y from marker message
 *
 * @return y position
 */
static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg)
{
lm's avatar
lm committed
196
	return MAVLINK_MSG_RETURN_float(msg,  4);
James Goppert's avatar
James Goppert committed
197 198 199 200 201 202 203 204 205
}

/**
 * @brief Get field z from marker message
 *
 * @return z position
 */
static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg)
{
lm's avatar
lm committed
206
	return MAVLINK_MSG_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
207 208 209 210 211 212 213 214 215
}

/**
 * @brief Get field roll from marker message
 *
 * @return roll orientation
 */
static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg)
{
lm's avatar
lm committed
216
	return MAVLINK_MSG_RETURN_float(msg,  12);
James Goppert's avatar
James Goppert committed
217 218 219 220 221 222 223 224 225
}

/**
 * @brief Get field pitch from marker message
 *
 * @return pitch orientation
 */
static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg)
{
lm's avatar
lm committed
226
	return MAVLINK_MSG_RETURN_float(msg,  16);
James Goppert's avatar
James Goppert committed
227 228 229 230 231 232 233 234 235
}

/**
 * @brief Get field yaw from marker message
 *
 * @return yaw orientation
 */
static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg)
{
lm's avatar
lm committed
236
	return MAVLINK_MSG_RETURN_float(msg,  20);
James Goppert's avatar
James Goppert committed
237 238 239 240 241 242 243 244 245 246
}

/**
 * @brief Decode a marker message into a struct
 *
 * @param msg The message to decode
 * @param marker C-struct to decode the message contents into
 */
static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker)
{
lm's avatar
lm committed
247 248 249 250 251 252 253 254 255 256 257
#if MAVLINK_NEED_BYTE_SWAP
	marker->x = mavlink_msg_marker_get_x(msg);
	marker->y = mavlink_msg_marker_get_y(msg);
	marker->z = mavlink_msg_marker_get_z(msg);
	marker->roll = mavlink_msg_marker_get_roll(msg);
	marker->pitch = mavlink_msg_marker_get_pitch(msg);
	marker->yaw = mavlink_msg_marker_get_yaw(msg);
	marker->id = mavlink_msg_marker_get_id(msg);
#else
	memcpy(marker, MAVLINK_PAYLOAD(msg), 26);
#endif
James Goppert's avatar
James Goppert committed
258
}