// MESSAGE MARKER PACKING #define MAVLINK_MSG_ID_MARKER 130 typedef struct __mavlink_marker_t { uint16_t id; ///< ID float x; ///< x position float y; ///< y position float z; ///< z position float roll; ///< roll orientation float pitch; ///< pitch orientation float yaw; ///< yaw orientation } mavlink_marker_t; /** * @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) */ 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) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_MARKER; i += put_uint16_t_by_index(id, i, msg->payload); // ID i += put_float_by_index(x, i, msg->payload); // x position i += put_float_by_index(y, i, msg->payload); // y position i += put_float_by_index(z, i, msg->payload); // z position i += put_float_by_index(roll, i, msg->payload); // roll orientation i += put_float_by_index(pitch, i, msg->payload); // pitch orientation i += put_float_by_index(yaw, i, msg->payload); // yaw orientation return mavlink_finalize_message(msg, system_id, component_id, i); } /** * @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 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) */ 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) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_MARKER; i += put_uint16_t_by_index(id, i, msg->payload); // ID i += put_float_by_index(x, i, msg->payload); // x position i += put_float_by_index(y, i, msg->payload); // y position i += put_float_by_index(z, i, msg->payload); // z position i += put_float_by_index(roll, i, msg->payload); // roll orientation i += put_float_by_index(pitch, i, msg->payload); // pitch orientation i += put_float_by_index(yaw, i, msg->payload); // yaw orientation return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } /** * @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 */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 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) { mavlink_message_t msg; mavlink_msg_marker_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, roll, pitch, yaw); mavlink_send_uart(chan, &msg); } #endif // MESSAGE MARKER UNPACKING /** * @brief Get field id from marker message * * @return ID */ static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg) { generic_16bit r; r.b[1] = (msg->payload)[0]; r.b[0] = (msg->payload)[1]; return (uint16_t)r.s; } /** * @brief Get field x from marker message * * @return x position */ static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg) { generic_32bit r; r.b[3] = (msg->payload+sizeof(uint16_t))[0]; r.b[2] = (msg->payload+sizeof(uint16_t))[1]; r.b[1] = (msg->payload+sizeof(uint16_t))[2]; r.b[0] = (msg->payload+sizeof(uint16_t))[3]; return (float)r.f; } /** * @brief Get field y from marker message * * @return y position */ static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg) { generic_32bit r; r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0]; r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1]; r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2]; r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3]; return (float)r.f; } /** * @brief Get field z from marker message * * @return z position */ static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg) { generic_32bit r; r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; return (float)r.f; } /** * @brief Get field roll from marker message * * @return roll orientation */ static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg) { generic_32bit r; r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; return (float)r.f; } /** * @brief Get field pitch from marker message * * @return pitch orientation */ static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg) { generic_32bit r; r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; return (float)r.f; } /** * @brief Get field yaw from marker message * * @return yaw orientation */ static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg) { generic_32bit r; r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; return (float)r.f; } /** * @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) { marker->id = mavlink_msg_marker_get_id(msg); 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); }