mavlink_msg_roll_pitch_yaw_thrust_setpoint.h 8.61 KB
Newer Older
lm's avatar
lm committed
1 2
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING

3
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58
lm's avatar
lm committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t
lm's avatar
lm committed
6
{
7
 uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
lm's avatar
lm committed
8 9 10 11
 float roll; ///< Desired roll angle in radians
 float pitch; ///< Desired pitch angle in radians
 float yaw; ///< Desired yaw angle in radians
 float thrust; ///< Collective thrust, normalized to 0 .. 1
lm's avatar
lm committed
12 13
} mavlink_roll_pitch_yaw_thrust_setpoint_t;

lm's avatar
lm committed
14
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20
15
#define MAVLINK_MSG_ID_58_LEN 20
lm's avatar
lm committed
16 17 18 19 20 21



#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \
	"ROLL_PITCH_YAW_THRUST_SETPOINT", \
	5, \
lm's avatar
lm committed
22 23 24 25 26
	{  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_boot_ms) }, \
         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \
         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \
         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \
         { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \
lm's avatar
lm committed
27 28 29 30
         } \
}


lm's avatar
lm committed
31 32 33 34 35 36
/**
 * @brief Pack a roll_pitch_yaw_thrust_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
 *
37
 * @param time_boot_ms Timestamp in milliseconds since system boot
lm's avatar
lm committed
38 39 40 41 42 43
 * @param roll Desired roll angle in radians
 * @param pitch Desired pitch angle in radians
 * @param yaw Desired yaw angle in radians
 * @param thrust Collective thrust, normalized to 0 .. 1
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
44
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45
						       uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust)
lm's avatar
lm committed
46
{
LM's avatar
LM committed
47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[20];
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_float(buf, 4, roll);
	_mav_put_float(buf, 8, pitch);
	_mav_put_float(buf, 12, yaw);
	_mav_put_float(buf, 16, thrust);

        memcpy(_MAV_PAYLOAD(msg), buf, 20);
#else
	mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.roll = roll;
	packet.pitch = pitch;
	packet.yaw = yaw;
	packet.thrust = thrust;

        memcpy(_MAV_PAYLOAD(msg), &packet, 20);
#endif
lm's avatar
lm committed
66

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

/**
lm's avatar
lm committed
72
 * @brief Pack a roll_pitch_yaw_thrust_setpoint message on a channel
lm's avatar
lm 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
77
 * @param time_boot_ms Timestamp in milliseconds since system boot
lm's avatar
lm committed
78 79 80 81 82 83
 * @param roll Desired roll angle in radians
 * @param pitch Desired pitch angle in radians
 * @param yaw Desired yaw angle in radians
 * @param thrust Collective thrust, normalized to 0 .. 1
 * @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_roll_pitch_yaw_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
86
						           uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust)
lm's avatar
lm committed
87
{
LM's avatar
LM committed
88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[20];
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_float(buf, 4, roll);
	_mav_put_float(buf, 8, pitch);
	_mav_put_float(buf, 12, yaw);
	_mav_put_float(buf, 16, thrust);

        memcpy(_MAV_PAYLOAD(msg), buf, 20);
#else
	mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.roll = roll;
	packet.pitch = pitch;
	packet.yaw = yaw;
	packet.thrust = thrust;

        memcpy(_MAV_PAYLOAD(msg), &packet, 20);
#endif
lm's avatar
lm committed
107

LM's avatar
LM committed
108
	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
109
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 239);
lm's avatar
lm committed
110 111 112 113 114 115 116 117 118 119 120 121
}

/**
 * @brief Encode a roll_pitch_yaw_thrust_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 roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
{
122
	return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust);
lm's avatar
lm committed
123 124 125 126 127 128
}

/**
 * @brief Send a roll_pitch_yaw_thrust_setpoint message
 * @param chan MAVLink channel to send the message
 *
129
 * @param time_boot_ms Timestamp in milliseconds since system boot
lm's avatar
lm committed
130 131 132 133 134
 * @param roll Desired roll angle in radians
 * @param pitch Desired pitch angle in radians
 * @param yaw Desired yaw angle in radians
 * @param thrust Collective thrust, normalized to 0 .. 1
 */
lm's avatar
lm committed
135 136
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

137
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust)
lm's avatar
lm committed
138
{
LM's avatar
LM committed
139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[20];
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_float(buf, 4, roll);
	_mav_put_float(buf, 8, pitch);
	_mav_put_float(buf, 12, yaw);
	_mav_put_float(buf, 16, thrust);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, 20, 239);
#else
	mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.roll = roll;
	packet.pitch = pitch;
	packet.yaw = yaw;
	packet.thrust = thrust;

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, 20, 239);
#endif
lm's avatar
lm committed
158 159 160
}

#endif
lm's avatar
lm committed
161

lm's avatar
lm committed
162 163
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING

lm's avatar
lm committed
164

lm's avatar
lm committed
165
/**
166
 * @brief Get field time_boot_ms from roll_pitch_yaw_thrust_setpoint message
lm's avatar
lm committed
167 168 169
 *
 * @return Timestamp in milliseconds since system boot
 */
170
static inline uint32_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
lm's avatar
lm committed
171
{
LM's avatar
LM committed
172
	return _MAV_RETURN_uint32_t(msg,  0);
lm's avatar
lm committed
173 174 175 176 177 178 179 180 181
}

/**
 * @brief Get field roll from roll_pitch_yaw_thrust_setpoint message
 *
 * @return Desired roll angle in radians
 */
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg)
{
LM's avatar
LM committed
182
	return _MAV_RETURN_float(msg,  4);
lm's avatar
lm committed
183 184 185 186 187 188 189 190 191
}

/**
 * @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message
 *
 * @return Desired pitch angle in radians
 */
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg)
{
LM's avatar
LM committed
192
	return _MAV_RETURN_float(msg,  8);
lm's avatar
lm committed
193 194 195 196 197 198 199 200 201
}

/**
 * @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message
 *
 * @return Desired yaw angle in radians
 */
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg)
{
LM's avatar
LM committed
202
	return _MAV_RETURN_float(msg,  12);
lm's avatar
lm committed
203 204 205 206 207 208 209 210 211
}

/**
 * @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message
 *
 * @return Collective thrust, normalized to 0 .. 1
 */
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
LM's avatar
LM committed
212
	return _MAV_RETURN_float(msg,  16);
lm's avatar
lm committed
213 214 215 216 217 218 219 220 221 222
}

/**
 * @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct
 *
 * @param msg The message to decode
 * @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into
 */
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
{
lm's avatar
lm committed
223
#if MAVLINK_NEED_BYTE_SWAP
224
	roll_pitch_yaw_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(msg);
lm's avatar
lm committed
225 226 227 228 229
	roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg);
	roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg);
	roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg);
	roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg);
#else
LM's avatar
LM committed
230
	memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), 20);
lm's avatar
lm committed
231
#endif
lm's avatar
lm committed
232
}