mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h 9.01 KB
Newer Older
lm's avatar
lm committed
1 2
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING

3
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59
lm's avatar
lm committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_roll_pitch_yaw_speed_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_speed; ///< Desired roll angular speed in rad/s
 float pitch_speed; ///< Desired pitch angular speed in rad/s
 float yaw_speed; ///< Desired yaw angular speed in rad/s
 float thrust; ///< Collective thrust, normalized to 0 .. 1
lm's avatar
lm committed
12 13
} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t;

lm's avatar
lm committed
14
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20
15
#define MAVLINK_MSG_ID_59_LEN 20
lm's avatar
lm committed
16 17 18 19 20 21



#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \
	"ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \
	5, \
22
	{  { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_boot_ms) }, \
lm's avatar
lm committed
23 24 25 26 27 28 29 30
         { "roll_speed", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \
         { "pitch_speed", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \
         { "yaw_speed", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \
         { "thrust", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \
         } \
}


lm's avatar
lm committed
31 32 33 34 35 36
/**
 * @brief Pack a roll_pitch_yaw_speed_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_speed Desired roll angular speed in rad/s
 * @param pitch_speed Desired pitch angular speed in rad/s
 * @param yaw_speed Desired yaw angular speed in rad/s
 * @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_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45
						       uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
lm's avatar
lm committed
46 47 48
{
	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;

49
	put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp in milliseconds since system boot
lm's avatar
lm committed
50 51 52 53
	put_float_by_index(msg, 4, roll_speed); // Desired roll angular speed in rad/s
	put_float_by_index(msg, 8, pitch_speed); // Desired pitch angular speed in rad/s
	put_float_by_index(msg, 12, yaw_speed); // Desired yaw angular speed in rad/s
	put_float_by_index(msg, 16, thrust); // Collective thrust, normalized to 0 .. 1
lm's avatar
lm committed
54

55
	return mavlink_finalize_message(msg, system_id, component_id, 20, 238);
lm's avatar
lm committed
56 57 58
}

/**
lm's avatar
lm committed
59
 * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message on a channel
lm's avatar
lm committed
60 61 62 63
 * @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
64
 * @param time_boot_ms Timestamp in milliseconds since system boot
lm's avatar
lm committed
65 66 67 68 69 70
 * @param roll_speed Desired roll angular speed in rad/s
 * @param pitch_speed Desired pitch angular speed in rad/s
 * @param yaw_speed Desired yaw angular speed in rad/s
 * @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
71 72
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
73
						           uint32_t time_boot_ms,float roll_speed,float pitch_speed,float yaw_speed,float thrust)
lm's avatar
lm committed
74 75 76
{
	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;

77
	put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp in milliseconds since system boot
lm's avatar
lm committed
78 79 80 81
	put_float_by_index(msg, 4, roll_speed); // Desired roll angular speed in rad/s
	put_float_by_index(msg, 8, pitch_speed); // Desired pitch angular speed in rad/s
	put_float_by_index(msg, 12, yaw_speed); // Desired yaw angular speed in rad/s
	put_float_by_index(msg, 16, thrust); // Collective thrust, normalized to 0 .. 1
lm's avatar
lm committed
82

83
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 238);
lm's avatar
lm committed
84 85 86 87 88 89 90 91 92 93 94 95
}

/**
 * @brief Encode a roll_pitch_yaw_speed_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_speed_thrust_setpoint C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
{
96
	return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust);
lm's avatar
lm committed
97 98 99 100 101 102
}

/**
 * @brief Send a roll_pitch_yaw_speed_thrust_setpoint message
 * @param chan MAVLink channel to send the message
 *
103
 * @param time_boot_ms Timestamp in milliseconds since system boot
lm's avatar
lm committed
104 105 106 107 108
 * @param roll_speed Desired roll angular speed in rad/s
 * @param pitch_speed Desired pitch angular speed in rad/s
 * @param yaw_speed Desired yaw angular speed in rad/s
 * @param thrust Collective thrust, normalized to 0 .. 1
 */
lm's avatar
lm committed
109 110
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

111
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
lm's avatar
lm committed
112
{
lm's avatar
lm committed
113
	MAVLINK_ALIGNED_MESSAGE(msg, 20);
LM's avatar
LM committed
114 115
	msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;

116
	put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp in milliseconds since system boot
LM's avatar
LM committed
117 118 119 120 121
	put_float_by_index(msg, 4, roll_speed); // Desired roll angular speed in rad/s
	put_float_by_index(msg, 8, pitch_speed); // Desired pitch angular speed in rad/s
	put_float_by_index(msg, 12, yaw_speed); // Desired yaw angular speed in rad/s
	put_float_by_index(msg, 16, thrust); // Collective thrust, normalized to 0 .. 1

122
	mavlink_finalize_message_chan_send(msg, chan, 20, 238);
lm's avatar
lm committed
123 124 125
}

#endif
lm's avatar
lm committed
126

lm's avatar
lm committed
127 128
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING

lm's avatar
lm committed
129

lm's avatar
lm committed
130
/**
131
 * @brief Get field time_boot_ms from roll_pitch_yaw_speed_thrust_setpoint message
lm's avatar
lm committed
132 133 134
 *
 * @return Timestamp in milliseconds since system boot
 */
135
static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
lm's avatar
lm committed
136
{
lm's avatar
lm committed
137
	return MAVLINK_MSG_RETURN_uint32_t(msg,  0);
lm's avatar
lm committed
138 139 140 141 142 143 144 145 146
}

/**
 * @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message
 *
 * @return Desired roll angular speed in rad/s
 */
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg)
{
lm's avatar
lm committed
147
	return MAVLINK_MSG_RETURN_float(msg,  4);
lm's avatar
lm committed
148 149 150 151 152 153 154 155 156
}

/**
 * @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message
 *
 * @return Desired pitch angular speed in rad/s
 */
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg)
{
lm's avatar
lm committed
157
	return MAVLINK_MSG_RETURN_float(msg,  8);
lm's avatar
lm committed
158 159 160 161 162 163 164 165 166
}

/**
 * @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message
 *
 * @return Desired yaw angular speed in rad/s
 */
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg)
{
lm's avatar
lm committed
167
	return MAVLINK_MSG_RETURN_float(msg,  12);
lm's avatar
lm committed
168 169 170 171 172 173 174 175 176
}

/**
 * @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message
 *
 * @return Collective thrust, normalized to 0 .. 1
 */
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
lm's avatar
lm committed
177
	return MAVLINK_MSG_RETURN_float(msg,  16);
lm's avatar
lm committed
178 179 180 181 182 183 184 185 186 187
}

/**
 * @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct
 *
 * @param msg The message to decode
 * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into
 */
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
{
lm's avatar
lm committed
188
#if MAVLINK_NEED_BYTE_SWAP
189
	roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(msg);
lm's avatar
lm committed
190 191 192 193 194 195 196
	roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg);
	roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg);
	roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg);
	roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg);
#else
	memcpy(roll_pitch_yaw_speed_thrust_setpoint, MAVLINK_PAYLOAD(msg), 20);
#endif
lm's avatar
lm committed
197
}