3 #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146 26 #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100 27 #define MAVLINK_MSG_ID_146_LEN 100 29 #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103 30 #define MAVLINK_MSG_ID_146_CRC 103 32 #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3 33 #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3 34 #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4 36 #define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ 37 "CONTROL_SYSTEM_STATE", \ 39 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ 40 { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ 41 { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ 42 { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ 43 { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ 44 { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ 45 { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ 46 { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ 47 { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ 48 { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ 49 { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ 50 { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ 51 { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ 52 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ 53 { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ 54 { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ 55 { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ 86 uint64_t
time_usec,
float x_acc,
float y_acc,
float z_acc,
float x_vel,
float y_vel,
float z_vel,
float x_pos,
float y_pos,
float z_pos,
float airspeed,
const float *
vel_variance,
const float *
pos_variance,
const float *
q,
float roll_rate,
float pitch_rate,
float yaw_rate)
88 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 104 _mav_put_float_array(buf, 48, vel_variance, 3);
105 _mav_put_float_array(buf, 60, pos_variance, 3);
106 _mav_put_float_array(buf, 72, q, 4);
131 #if MAVLINK_CRC_EXTRA 164 mavlink_message_t* msg,
165 uint64_t
time_usec,
float x_acc,
float y_acc,
float z_acc,
float x_vel,
float y_vel,
float z_vel,
float x_pos,
float y_pos,
float z_pos,
float airspeed,
const float *
vel_variance,
const float *
pos_variance,
const float *
q,
float roll_rate,
float pitch_rate,
float yaw_rate)
167 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 183 _mav_put_float_array(buf, 48, vel_variance, 3);
184 _mav_put_float_array(buf, 60, pos_variance, 3);
185 _mav_put_float_array(buf, 72, q, 4);
210 #if MAVLINK_CRC_EXTRA 227 return mavlink_msg_control_system_state_pack(system_id, component_id, msg, control_system_state->
time_usec, control_system_state->
x_acc, control_system_state->
y_acc, control_system_state->
z_acc, control_system_state->
x_vel, control_system_state->
y_vel, control_system_state->
z_vel, control_system_state->
x_pos, control_system_state->
y_pos, control_system_state->
z_pos, control_system_state->
airspeed, control_system_state->
vel_variance, control_system_state->
pos_variance, control_system_state->
q, control_system_state->
roll_rate, control_system_state->
pitch_rate, control_system_state->
yaw_rate);
241 return mavlink_msg_control_system_state_pack_chan(system_id, component_id, chan, msg, control_system_state->
time_usec, control_system_state->
x_acc, control_system_state->
y_acc, control_system_state->
z_acc, control_system_state->
x_vel, control_system_state->
y_vel, control_system_state->
z_vel, control_system_state->
x_pos, control_system_state->
y_pos, control_system_state->
z_pos, control_system_state->
airspeed, control_system_state->
vel_variance, control_system_state->
pos_variance, control_system_state->
q, control_system_state->
roll_rate, control_system_state->
pitch_rate, control_system_state->
yaw_rate);
266 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 268 static inline void mavlink_msg_control_system_state_send(
mavlink_channel_t chan, uint64_t
time_usec,
float x_acc,
float y_acc,
float z_acc,
float x_vel,
float y_vel,
float z_vel,
float x_pos,
float y_pos,
float z_pos,
float airspeed,
const float *
vel_variance,
const float *
pos_variance,
const float *
q,
float roll_rate,
float pitch_rate,
float yaw_rate)
270 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 288 _mav_put_float_array(buf, 72,
q, 4);
289 #if MAVLINK_CRC_EXTRA 313 #if MAVLINK_CRC_EXTRA 321 #if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN 329 static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t
time_usec,
float x_acc,
float y_acc,
float z_acc,
float x_vel,
float y_vel,
float z_vel,
float x_pos,
float y_pos,
float z_pos,
float airspeed,
const float *
vel_variance,
const float *
pos_variance,
const float *
q,
float roll_rate,
float pitch_rate,
float yaw_rate)
331 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 332 char *buf = (
char *)msgbuf;
349 _mav_put_float_array(buf, 72,
q, 4);
350 #if MAVLINK_CRC_EXTRA 374 #if MAVLINK_CRC_EXTRA 395 return _MAV_RETURN_uint64_t(msg, 0);
405 return _MAV_RETURN_float(msg, 8);
415 return _MAV_RETURN_float(msg, 12);
425 return _MAV_RETURN_float(msg, 16);
435 return _MAV_RETURN_float(msg, 20);
445 return _MAV_RETURN_float(msg, 24);
455 return _MAV_RETURN_float(msg, 28);
465 return _MAV_RETURN_float(msg, 32);
475 return _MAV_RETURN_float(msg, 36);
485 return _MAV_RETURN_float(msg, 40);
495 return _MAV_RETURN_float(msg, 44);
505 return _MAV_RETURN_float_array(msg, vel_variance, 3, 48);
515 return _MAV_RETURN_float_array(msg, pos_variance, 3, 60);
525 return _MAV_RETURN_float_array(msg, q, 4, 72);
535 return _MAV_RETURN_float(msg, 88);
545 return _MAV_RETURN_float(msg, 92);
555 return _MAV_RETURN_float(msg, 96);
566 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t *msg)
Get field x_acc from control_system_state message.
static float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t *msg)
Get field roll_rate from control_system_state message.
static float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t *msg)
Get field y_pos from control_system_state message.
static float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t *msg)
Get field z_vel from control_system_state message.
static float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t *msg)
Get field y_acc from control_system_state message.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
struct __mavlink_control_system_state_t mavlink_control_system_state_t
static float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t *msg)
Get field z_pos from control_system_state message.
static float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t *msg)
Get field pitch_rate from control_system_state message.
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t *msg)
Get field y_vel from control_system_state message.
static uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate)
Pack a control_system_state message.
static float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t *msg)
Get field yaw_rate from control_system_state message.
static float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t *msg)
Get field x_vel from control_system_state message.
#define _MAV_PAYLOAD(msg)
static float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t *msg)
Get field x_pos from control_system_state message.
static uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t *msg, float *q)
Get field q from control_system_state message.
#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE
static float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t *msg)
Get field airspeed from control_system_state message.
static uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t *msg, float *pos_variance)
Get field pos_variance from control_system_state message.
static uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t *msg)
Send a control_system_state message.
#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN
static void mavlink_msg_control_system_state_decode(const mavlink_message_t *msg, mavlink_control_system_state_t *control_system_state)
Decode a control_system_state message into a struct.
#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC
static float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t *msg)
Get field z_acc from control_system_state message.
static uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_control_system_state_t *control_system_state)
Encode a control_system_state struct on a channel.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t *msg, float *vel_variance)
Get field vel_variance from control_system_state message.
static uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate)
Pack a control_system_state message on a channel.
static uint16_t mavlink_msg_control_system_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_control_system_state_t *control_system_state)
Encode a control_system_state struct.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.