mavlink_msg_position_target.h 5.89 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE POSITION_TARGET PACKING

#define MAVLINK_MSG_ID_POSITION_TARGET 63
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_POSITION_TARGET_LEN 16
#define MAVLINK_MSG_63_LEN 16
James Goppert's avatar
James Goppert committed
6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29

typedef struct __mavlink_position_target_t 
{
	float x; ///< x position
	float y; ///< y position
	float z; ///< z position
	float yaw; ///< yaw orientation in radians, 0 = NORTH

} mavlink_position_target_t;

/**
 * @brief Pack a position_target 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 x x position
 * @param y y position
 * @param z z position
 * @param yaw yaw orientation in radians, 0 = NORTH
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw)
{
lm's avatar
lm committed
30
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
31 32
	msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;

lm's avatar
lm committed
33 34 35 36
	p->x = x; // float:x position
	p->y = y; // float:y position
	p->z = z; // float:z position
	p->yaw = yaw; // float:yaw orientation in radians, 0 = NORTH
James Goppert's avatar
James Goppert committed
37

lm's avatar
lm committed
38
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LEN);
James Goppert's avatar
James Goppert committed
39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54
}

/**
 * @brief Pack a position_target 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 x x position
 * @param y y position
 * @param z z position
 * @param yaw yaw orientation in radians, 0 = NORTH
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
{
lm's avatar
lm committed
55
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
56 57
	msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;

lm's avatar
lm committed
58 59 60 61
	p->x = x; // float:x position
	p->y = y; // float:y position
	p->z = z; // float:z position
	p->yaw = yaw; // float:yaw orientation in radians, 0 = NORTH
James Goppert's avatar
James Goppert committed
62

lm's avatar
lm committed
63
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LEN);
James Goppert's avatar
James Goppert committed
64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87
}

/**
 * @brief Encode a position_target 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 position_target C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target)
{
	return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw);
}

/**
 * @brief Send a position_target message
 * @param chan MAVLink channel to send the message
 *
 * @param x x position
 * @param y y position
 * @param z z position
 * @param yaw yaw orientation in radians, 0 = NORTH
 */
lm's avatar
lm committed
88 89


90
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
lm's avatar
lm committed
91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119
static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
{
	mavlink_header_t hdr;
	mavlink_position_target_t payload;
	uint16_t checksum;
	mavlink_position_target_t *p = &payload;

	p->x = x; // float:x position
	p->y = y; // float:y position
	p->z = z; // float:z position
	p->yaw = yaw; // float:yaw orientation in radians, 0 = NORTH

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_POSITION_TARGET_LEN;
	hdr.msgid = MAVLINK_MSG_ID_POSITION_TARGET;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );

	crc_init(&checksum);
	checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
	checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
	hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
James Goppert's avatar
James Goppert committed
120 121 122 123 124 125 126 127 128 129 130 131
}

#endif
// MESSAGE POSITION_TARGET UNPACKING

/**
 * @brief Get field x from position_target message
 *
 * @return x position
 */
static inline float mavlink_msg_position_target_get_x(const mavlink_message_t* msg)
{
lm's avatar
lm committed
132 133
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->x);
James Goppert's avatar
James Goppert committed
134 135 136 137 138 139 140 141 142
}

/**
 * @brief Get field y from position_target message
 *
 * @return y position
 */
static inline float mavlink_msg_position_target_get_y(const mavlink_message_t* msg)
{
lm's avatar
lm committed
143 144
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->y);
James Goppert's avatar
James Goppert committed
145 146 147 148 149 150 151 152 153
}

/**
 * @brief Get field z from position_target message
 *
 * @return z position
 */
static inline float mavlink_msg_position_target_get_z(const mavlink_message_t* msg)
{
lm's avatar
lm committed
154 155
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->z);
James Goppert's avatar
James Goppert committed
156 157 158 159 160 161 162 163 164
}

/**
 * @brief Get field yaw from position_target message
 *
 * @return yaw orientation in radians, 0 = NORTH
 */
static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t* msg)
{
lm's avatar
lm committed
165 166
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->yaw);
James Goppert's avatar
James Goppert committed
167 168 169 170 171 172 173 174 175 176
}

/**
 * @brief Decode a position_target message into a struct
 *
 * @param msg The message to decode
 * @param position_target C-struct to decode the message contents into
 */
static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target)
{
lm's avatar
lm committed
177
	memcpy( position_target, msg->payload, sizeof(mavlink_position_target_t));
James Goppert's avatar
James Goppert committed
178
}