[88] | 1 | // MESSAGE CONTROL_SYSTEM_STATE PACKING
|
---|
| 2 |
|
---|
| 3 | #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146
|
---|
| 4 |
|
---|
| 5 | typedef struct MAVLINK_PACKED __mavlink_control_system_state_t
|
---|
| 6 | {
|
---|
| 7 | uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
|
---|
| 8 | float x_acc; /*< X acceleration in body frame*/
|
---|
| 9 | float y_acc; /*< Y acceleration in body frame*/
|
---|
| 10 | float z_acc; /*< Z acceleration in body frame*/
|
---|
| 11 | float x_vel; /*< X velocity in body frame*/
|
---|
| 12 | float y_vel; /*< Y velocity in body frame*/
|
---|
| 13 | float z_vel; /*< Z velocity in body frame*/
|
---|
| 14 | float x_pos; /*< X position in local frame*/
|
---|
| 15 | float y_pos; /*< Y position in local frame*/
|
---|
| 16 | float z_pos; /*< Z position in local frame*/
|
---|
| 17 | float airspeed; /*< Airspeed, set to -1 if unknown*/
|
---|
| 18 | float vel_variance[3]; /*< Variance of body velocity estimate*/
|
---|
| 19 | float pos_variance[3]; /*< Variance in local position*/
|
---|
| 20 | float q[4]; /*< The attitude, represented as Quaternion*/
|
---|
| 21 | float roll_rate; /*< Angular rate in roll axis*/
|
---|
| 22 | float pitch_rate; /*< Angular rate in pitch axis*/
|
---|
| 23 | float yaw_rate; /*< Angular rate in yaw axis*/
|
---|
| 24 | } mavlink_control_system_state_t;
|
---|
| 25 |
|
---|
| 26 | #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100
|
---|
| 27 | #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN 100
|
---|
| 28 | #define MAVLINK_MSG_ID_146_LEN 100
|
---|
| 29 | #define MAVLINK_MSG_ID_146_MIN_LEN 100
|
---|
| 30 |
|
---|
| 31 | #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103
|
---|
| 32 | #define MAVLINK_MSG_ID_146_CRC 103
|
---|
| 33 |
|
---|
| 34 | #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3
|
---|
| 35 | #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3
|
---|
| 36 | #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4
|
---|
| 37 |
|
---|
| 38 | #if MAVLINK_COMMAND_24BIT
|
---|
| 39 | #define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \
|
---|
| 40 | 146, \
|
---|
| 41 | "CONTROL_SYSTEM_STATE", \
|
---|
| 42 | 17, \
|
---|
| 43 | { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \
|
---|
| 44 | { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \
|
---|
| 45 | { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \
|
---|
| 46 | { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \
|
---|
| 47 | { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \
|
---|
| 48 | { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \
|
---|
| 49 | { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \
|
---|
| 50 | { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \
|
---|
| 51 | { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \
|
---|
| 52 | { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \
|
---|
| 53 | { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \
|
---|
| 54 | { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \
|
---|
| 55 | { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \
|
---|
| 56 | { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \
|
---|
| 57 | { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \
|
---|
| 58 | { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \
|
---|
| 59 | { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \
|
---|
| 60 | } \
|
---|
| 61 | }
|
---|
| 62 | #else
|
---|
| 63 | #define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \
|
---|
| 64 | "CONTROL_SYSTEM_STATE", \
|
---|
| 65 | 17, \
|
---|
| 66 | { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \
|
---|
| 67 | { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \
|
---|
| 68 | { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \
|
---|
| 69 | { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \
|
---|
| 70 | { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \
|
---|
| 71 | { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \
|
---|
| 72 | { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \
|
---|
| 73 | { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \
|
---|
| 74 | { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \
|
---|
| 75 | { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \
|
---|
| 76 | { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \
|
---|
| 77 | { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \
|
---|
| 78 | { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \
|
---|
| 79 | { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \
|
---|
| 80 | { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \
|
---|
| 81 | { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \
|
---|
| 82 | { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \
|
---|
| 83 | } \
|
---|
| 84 | }
|
---|
| 85 | #endif
|
---|
| 86 |
|
---|
| 87 | /**
|
---|
| 88 | * @brief Pack a control_system_state message
|
---|
| 89 | * @param system_id ID of this system
|
---|
| 90 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 91 | * @param msg The MAVLink message to compress the data into
|
---|
| 92 | *
|
---|
| 93 | * @param time_usec Timestamp (micros since boot or Unix epoch)
|
---|
| 94 | * @param x_acc X acceleration in body frame
|
---|
| 95 | * @param y_acc Y acceleration in body frame
|
---|
| 96 | * @param z_acc Z acceleration in body frame
|
---|
| 97 | * @param x_vel X velocity in body frame
|
---|
| 98 | * @param y_vel Y velocity in body frame
|
---|
| 99 | * @param z_vel Z velocity in body frame
|
---|
| 100 | * @param x_pos X position in local frame
|
---|
| 101 | * @param y_pos Y position in local frame
|
---|
| 102 | * @param z_pos Z position in local frame
|
---|
| 103 | * @param airspeed Airspeed, set to -1 if unknown
|
---|
| 104 | * @param vel_variance Variance of body velocity estimate
|
---|
| 105 | * @param pos_variance Variance in local position
|
---|
| 106 | * @param q The attitude, represented as Quaternion
|
---|
| 107 | * @param roll_rate Angular rate in roll axis
|
---|
| 108 | * @param pitch_rate Angular rate in pitch axis
|
---|
| 109 | * @param yaw_rate Angular rate in yaw axis
|
---|
| 110 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 111 | */
|
---|
| 112 | static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
| 113 | 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)
|
---|
| 114 | {
|
---|
| 115 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 116 | char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN];
|
---|
| 117 | _mav_put_uint64_t(buf, 0, time_usec);
|
---|
| 118 | _mav_put_float(buf, 8, x_acc);
|
---|
| 119 | _mav_put_float(buf, 12, y_acc);
|
---|
| 120 | _mav_put_float(buf, 16, z_acc);
|
---|
| 121 | _mav_put_float(buf, 20, x_vel);
|
---|
| 122 | _mav_put_float(buf, 24, y_vel);
|
---|
| 123 | _mav_put_float(buf, 28, z_vel);
|
---|
| 124 | _mav_put_float(buf, 32, x_pos);
|
---|
| 125 | _mav_put_float(buf, 36, y_pos);
|
---|
| 126 | _mav_put_float(buf, 40, z_pos);
|
---|
| 127 | _mav_put_float(buf, 44, airspeed);
|
---|
| 128 | _mav_put_float(buf, 88, roll_rate);
|
---|
| 129 | _mav_put_float(buf, 92, pitch_rate);
|
---|
| 130 | _mav_put_float(buf, 96, yaw_rate);
|
---|
| 131 | _mav_put_float_array(buf, 48, vel_variance, 3);
|
---|
| 132 | _mav_put_float_array(buf, 60, pos_variance, 3);
|
---|
| 133 | _mav_put_float_array(buf, 72, q, 4);
|
---|
| 134 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
|
---|
| 135 | #else
|
---|
| 136 | mavlink_control_system_state_t packet;
|
---|
| 137 | packet.time_usec = time_usec;
|
---|
| 138 | packet.x_acc = x_acc;
|
---|
| 139 | packet.y_acc = y_acc;
|
---|
| 140 | packet.z_acc = z_acc;
|
---|
| 141 | packet.x_vel = x_vel;
|
---|
| 142 | packet.y_vel = y_vel;
|
---|
| 143 | packet.z_vel = z_vel;
|
---|
| 144 | packet.x_pos = x_pos;
|
---|
| 145 | packet.y_pos = y_pos;
|
---|
| 146 | packet.z_pos = z_pos;
|
---|
| 147 | packet.airspeed = airspeed;
|
---|
| 148 | packet.roll_rate = roll_rate;
|
---|
| 149 | packet.pitch_rate = pitch_rate;
|
---|
| 150 | packet.yaw_rate = yaw_rate;
|
---|
| 151 | mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3);
|
---|
| 152 | mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3);
|
---|
| 153 | mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
---|
| 154 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
|
---|
| 155 | #endif
|
---|
| 156 |
|
---|
| 157 | msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE;
|
---|
| 158 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
|
---|
| 159 | }
|
---|
| 160 |
|
---|
| 161 | /**
|
---|
| 162 | * @brief Pack a control_system_state message on a channel
|
---|
| 163 | * @param system_id ID of this system
|
---|
| 164 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 165 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 166 | * @param msg The MAVLink message to compress the data into
|
---|
| 167 | * @param time_usec Timestamp (micros since boot or Unix epoch)
|
---|
| 168 | * @param x_acc X acceleration in body frame
|
---|
| 169 | * @param y_acc Y acceleration in body frame
|
---|
| 170 | * @param z_acc Z acceleration in body frame
|
---|
| 171 | * @param x_vel X velocity in body frame
|
---|
| 172 | * @param y_vel Y velocity in body frame
|
---|
| 173 | * @param z_vel Z velocity in body frame
|
---|
| 174 | * @param x_pos X position in local frame
|
---|
| 175 | * @param y_pos Y position in local frame
|
---|
| 176 | * @param z_pos Z position in local frame
|
---|
| 177 | * @param airspeed Airspeed, set to -1 if unknown
|
---|
| 178 | * @param vel_variance Variance of body velocity estimate
|
---|
| 179 | * @param pos_variance Variance in local position
|
---|
| 180 | * @param q The attitude, represented as Quaternion
|
---|
| 181 | * @param roll_rate Angular rate in roll axis
|
---|
| 182 | * @param pitch_rate Angular rate in pitch axis
|
---|
| 183 | * @param yaw_rate Angular rate in yaw axis
|
---|
| 184 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 185 | */
|
---|
| 186 | static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
| 187 | mavlink_message_t* msg,
|
---|
| 188 | 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)
|
---|
| 189 | {
|
---|
| 190 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 191 | char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN];
|
---|
| 192 | _mav_put_uint64_t(buf, 0, time_usec);
|
---|
| 193 | _mav_put_float(buf, 8, x_acc);
|
---|
| 194 | _mav_put_float(buf, 12, y_acc);
|
---|
| 195 | _mav_put_float(buf, 16, z_acc);
|
---|
| 196 | _mav_put_float(buf, 20, x_vel);
|
---|
| 197 | _mav_put_float(buf, 24, y_vel);
|
---|
| 198 | _mav_put_float(buf, 28, z_vel);
|
---|
| 199 | _mav_put_float(buf, 32, x_pos);
|
---|
| 200 | _mav_put_float(buf, 36, y_pos);
|
---|
| 201 | _mav_put_float(buf, 40, z_pos);
|
---|
| 202 | _mav_put_float(buf, 44, airspeed);
|
---|
| 203 | _mav_put_float(buf, 88, roll_rate);
|
---|
| 204 | _mav_put_float(buf, 92, pitch_rate);
|
---|
| 205 | _mav_put_float(buf, 96, yaw_rate);
|
---|
| 206 | _mav_put_float_array(buf, 48, vel_variance, 3);
|
---|
| 207 | _mav_put_float_array(buf, 60, pos_variance, 3);
|
---|
| 208 | _mav_put_float_array(buf, 72, q, 4);
|
---|
| 209 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
|
---|
| 210 | #else
|
---|
| 211 | mavlink_control_system_state_t packet;
|
---|
| 212 | packet.time_usec = time_usec;
|
---|
| 213 | packet.x_acc = x_acc;
|
---|
| 214 | packet.y_acc = y_acc;
|
---|
| 215 | packet.z_acc = z_acc;
|
---|
| 216 | packet.x_vel = x_vel;
|
---|
| 217 | packet.y_vel = y_vel;
|
---|
| 218 | packet.z_vel = z_vel;
|
---|
| 219 | packet.x_pos = x_pos;
|
---|
| 220 | packet.y_pos = y_pos;
|
---|
| 221 | packet.z_pos = z_pos;
|
---|
| 222 | packet.airspeed = airspeed;
|
---|
| 223 | packet.roll_rate = roll_rate;
|
---|
| 224 | packet.pitch_rate = pitch_rate;
|
---|
| 225 | packet.yaw_rate = yaw_rate;
|
---|
| 226 | mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3);
|
---|
| 227 | mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3);
|
---|
| 228 | mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
---|
| 229 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
|
---|
| 230 | #endif
|
---|
| 231 |
|
---|
| 232 | msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE;
|
---|
| 233 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
|
---|
| 234 | }
|
---|
| 235 |
|
---|
| 236 | /**
|
---|
| 237 | * @brief Encode a control_system_state struct
|
---|
| 238 | *
|
---|
| 239 | * @param system_id ID of this system
|
---|
| 240 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 241 | * @param msg The MAVLink message to compress the data into
|
---|
| 242 | * @param control_system_state C-struct to read the message contents from
|
---|
| 243 | */
|
---|
| 244 | static inline 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)
|
---|
| 245 | {
|
---|
| 246 | 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);
|
---|
| 247 | }
|
---|
| 248 |
|
---|
| 249 | /**
|
---|
| 250 | * @brief Encode a control_system_state struct on a channel
|
---|
| 251 | *
|
---|
| 252 | * @param system_id ID of this system
|
---|
| 253 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 254 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 255 | * @param msg The MAVLink message to compress the data into
|
---|
| 256 | * @param control_system_state C-struct to read the message contents from
|
---|
| 257 | */
|
---|
| 258 | static inline 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)
|
---|
| 259 | {
|
---|
| 260 | 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);
|
---|
| 261 | }
|
---|
| 262 |
|
---|
| 263 | /**
|
---|
| 264 | * @brief Send a control_system_state message
|
---|
| 265 | * @param chan MAVLink channel to send the message
|
---|
| 266 | *
|
---|
| 267 | * @param time_usec Timestamp (micros since boot or Unix epoch)
|
---|
| 268 | * @param x_acc X acceleration in body frame
|
---|
| 269 | * @param y_acc Y acceleration in body frame
|
---|
| 270 | * @param z_acc Z acceleration in body frame
|
---|
| 271 | * @param x_vel X velocity in body frame
|
---|
| 272 | * @param y_vel Y velocity in body frame
|
---|
| 273 | * @param z_vel Z velocity in body frame
|
---|
| 274 | * @param x_pos X position in local frame
|
---|
| 275 | * @param y_pos Y position in local frame
|
---|
| 276 | * @param z_pos Z position in local frame
|
---|
| 277 | * @param airspeed Airspeed, set to -1 if unknown
|
---|
| 278 | * @param vel_variance Variance of body velocity estimate
|
---|
| 279 | * @param pos_variance Variance in local position
|
---|
| 280 | * @param q The attitude, represented as Quaternion
|
---|
| 281 | * @param roll_rate Angular rate in roll axis
|
---|
| 282 | * @param pitch_rate Angular rate in pitch axis
|
---|
| 283 | * @param yaw_rate Angular rate in yaw axis
|
---|
| 284 | */
|
---|
| 285 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
| 286 |
|
---|
| 287 | 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)
|
---|
| 288 | {
|
---|
| 289 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 290 | char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN];
|
---|
| 291 | _mav_put_uint64_t(buf, 0, time_usec);
|
---|
| 292 | _mav_put_float(buf, 8, x_acc);
|
---|
| 293 | _mav_put_float(buf, 12, y_acc);
|
---|
| 294 | _mav_put_float(buf, 16, z_acc);
|
---|
| 295 | _mav_put_float(buf, 20, x_vel);
|
---|
| 296 | _mav_put_float(buf, 24, y_vel);
|
---|
| 297 | _mav_put_float(buf, 28, z_vel);
|
---|
| 298 | _mav_put_float(buf, 32, x_pos);
|
---|
| 299 | _mav_put_float(buf, 36, y_pos);
|
---|
| 300 | _mav_put_float(buf, 40, z_pos);
|
---|
| 301 | _mav_put_float(buf, 44, airspeed);
|
---|
| 302 | _mav_put_float(buf, 88, roll_rate);
|
---|
| 303 | _mav_put_float(buf, 92, pitch_rate);
|
---|
| 304 | _mav_put_float(buf, 96, yaw_rate);
|
---|
| 305 | _mav_put_float_array(buf, 48, vel_variance, 3);
|
---|
| 306 | _mav_put_float_array(buf, 60, pos_variance, 3);
|
---|
| 307 | _mav_put_float_array(buf, 72, q, 4);
|
---|
| 308 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
|
---|
| 309 | #else
|
---|
| 310 | mavlink_control_system_state_t packet;
|
---|
| 311 | packet.time_usec = time_usec;
|
---|
| 312 | packet.x_acc = x_acc;
|
---|
| 313 | packet.y_acc = y_acc;
|
---|
| 314 | packet.z_acc = z_acc;
|
---|
| 315 | packet.x_vel = x_vel;
|
---|
| 316 | packet.y_vel = y_vel;
|
---|
| 317 | packet.z_vel = z_vel;
|
---|
| 318 | packet.x_pos = x_pos;
|
---|
| 319 | packet.y_pos = y_pos;
|
---|
| 320 | packet.z_pos = z_pos;
|
---|
| 321 | packet.airspeed = airspeed;
|
---|
| 322 | packet.roll_rate = roll_rate;
|
---|
| 323 | packet.pitch_rate = pitch_rate;
|
---|
| 324 | packet.yaw_rate = yaw_rate;
|
---|
| 325 | mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3);
|
---|
| 326 | mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3);
|
---|
| 327 | mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
---|
| 328 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
|
---|
| 329 | #endif
|
---|
| 330 | }
|
---|
| 331 |
|
---|
| 332 | /**
|
---|
| 333 | * @brief Send a control_system_state message
|
---|
| 334 | * @param chan MAVLink channel to send the message
|
---|
| 335 | * @param struct The MAVLink struct to serialize
|
---|
| 336 | */
|
---|
| 337 | static inline void mavlink_msg_control_system_state_send_struct(mavlink_channel_t chan, const mavlink_control_system_state_t* control_system_state)
|
---|
| 338 | {
|
---|
| 339 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 340 | mavlink_msg_control_system_state_send(chan, 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);
|
---|
| 341 | #else
|
---|
| 342 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)control_system_state, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
|
---|
| 343 | #endif
|
---|
| 344 | }
|
---|
| 345 |
|
---|
| 346 | #if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
| 347 | /*
|
---|
| 348 | This varient of _send() can be used to save stack space by re-using
|
---|
| 349 | memory from the receive buffer. The caller provides a
|
---|
| 350 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
| 351 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
| 352 | incoming message with minimum stack space usage.
|
---|
| 353 | */
|
---|
| 354 | 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)
|
---|
| 355 | {
|
---|
| 356 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 357 | char *buf = (char *)msgbuf;
|
---|
| 358 | _mav_put_uint64_t(buf, 0, time_usec);
|
---|
| 359 | _mav_put_float(buf, 8, x_acc);
|
---|
| 360 | _mav_put_float(buf, 12, y_acc);
|
---|
| 361 | _mav_put_float(buf, 16, z_acc);
|
---|
| 362 | _mav_put_float(buf, 20, x_vel);
|
---|
| 363 | _mav_put_float(buf, 24, y_vel);
|
---|
| 364 | _mav_put_float(buf, 28, z_vel);
|
---|
| 365 | _mav_put_float(buf, 32, x_pos);
|
---|
| 366 | _mav_put_float(buf, 36, y_pos);
|
---|
| 367 | _mav_put_float(buf, 40, z_pos);
|
---|
| 368 | _mav_put_float(buf, 44, airspeed);
|
---|
| 369 | _mav_put_float(buf, 88, roll_rate);
|
---|
| 370 | _mav_put_float(buf, 92, pitch_rate);
|
---|
| 371 | _mav_put_float(buf, 96, yaw_rate);
|
---|
| 372 | _mav_put_float_array(buf, 48, vel_variance, 3);
|
---|
| 373 | _mav_put_float_array(buf, 60, pos_variance, 3);
|
---|
| 374 | _mav_put_float_array(buf, 72, q, 4);
|
---|
| 375 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
|
---|
| 376 | #else
|
---|
| 377 | mavlink_control_system_state_t *packet = (mavlink_control_system_state_t *)msgbuf;
|
---|
| 378 | packet->time_usec = time_usec;
|
---|
| 379 | packet->x_acc = x_acc;
|
---|
| 380 | packet->y_acc = y_acc;
|
---|
| 381 | packet->z_acc = z_acc;
|
---|
| 382 | packet->x_vel = x_vel;
|
---|
| 383 | packet->y_vel = y_vel;
|
---|
| 384 | packet->z_vel = z_vel;
|
---|
| 385 | packet->x_pos = x_pos;
|
---|
| 386 | packet->y_pos = y_pos;
|
---|
| 387 | packet->z_pos = z_pos;
|
---|
| 388 | packet->airspeed = airspeed;
|
---|
| 389 | packet->roll_rate = roll_rate;
|
---|
| 390 | packet->pitch_rate = pitch_rate;
|
---|
| 391 | packet->yaw_rate = yaw_rate;
|
---|
| 392 | mav_array_memcpy(packet->vel_variance, vel_variance, sizeof(float)*3);
|
---|
| 393 | mav_array_memcpy(packet->pos_variance, pos_variance, sizeof(float)*3);
|
---|
| 394 | mav_array_memcpy(packet->q, q, sizeof(float)*4);
|
---|
| 395 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
|
---|
| 396 | #endif
|
---|
| 397 | }
|
---|
| 398 | #endif
|
---|
| 399 |
|
---|
| 400 | #endif
|
---|
| 401 |
|
---|
| 402 | // MESSAGE CONTROL_SYSTEM_STATE UNPACKING
|
---|
| 403 |
|
---|
| 404 |
|
---|
| 405 | /**
|
---|
| 406 | * @brief Get field time_usec from control_system_state message
|
---|
| 407 | *
|
---|
| 408 | * @return Timestamp (micros since boot or Unix epoch)
|
---|
| 409 | */
|
---|
| 410 | static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg)
|
---|
| 411 | {
|
---|
| 412 | return _MAV_RETURN_uint64_t(msg, 0);
|
---|
| 413 | }
|
---|
| 414 |
|
---|
| 415 | /**
|
---|
| 416 | * @brief Get field x_acc from control_system_state message
|
---|
| 417 | *
|
---|
| 418 | * @return X acceleration in body frame
|
---|
| 419 | */
|
---|
| 420 | static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg)
|
---|
| 421 | {
|
---|
| 422 | return _MAV_RETURN_float(msg, 8);
|
---|
| 423 | }
|
---|
| 424 |
|
---|
| 425 | /**
|
---|
| 426 | * @brief Get field y_acc from control_system_state message
|
---|
| 427 | *
|
---|
| 428 | * @return Y acceleration in body frame
|
---|
| 429 | */
|
---|
| 430 | static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg)
|
---|
| 431 | {
|
---|
| 432 | return _MAV_RETURN_float(msg, 12);
|
---|
| 433 | }
|
---|
| 434 |
|
---|
| 435 | /**
|
---|
| 436 | * @brief Get field z_acc from control_system_state message
|
---|
| 437 | *
|
---|
| 438 | * @return Z acceleration in body frame
|
---|
| 439 | */
|
---|
| 440 | static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg)
|
---|
| 441 | {
|
---|
| 442 | return _MAV_RETURN_float(msg, 16);
|
---|
| 443 | }
|
---|
| 444 |
|
---|
| 445 | /**
|
---|
| 446 | * @brief Get field x_vel from control_system_state message
|
---|
| 447 | *
|
---|
| 448 | * @return X velocity in body frame
|
---|
| 449 | */
|
---|
| 450 | static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg)
|
---|
| 451 | {
|
---|
| 452 | return _MAV_RETURN_float(msg, 20);
|
---|
| 453 | }
|
---|
| 454 |
|
---|
| 455 | /**
|
---|
| 456 | * @brief Get field y_vel from control_system_state message
|
---|
| 457 | *
|
---|
| 458 | * @return Y velocity in body frame
|
---|
| 459 | */
|
---|
| 460 | static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg)
|
---|
| 461 | {
|
---|
| 462 | return _MAV_RETURN_float(msg, 24);
|
---|
| 463 | }
|
---|
| 464 |
|
---|
| 465 | /**
|
---|
| 466 | * @brief Get field z_vel from control_system_state message
|
---|
| 467 | *
|
---|
| 468 | * @return Z velocity in body frame
|
---|
| 469 | */
|
---|
| 470 | static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg)
|
---|
| 471 | {
|
---|
| 472 | return _MAV_RETURN_float(msg, 28);
|
---|
| 473 | }
|
---|
| 474 |
|
---|
| 475 | /**
|
---|
| 476 | * @brief Get field x_pos from control_system_state message
|
---|
| 477 | *
|
---|
| 478 | * @return X position in local frame
|
---|
| 479 | */
|
---|
| 480 | static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg)
|
---|
| 481 | {
|
---|
| 482 | return _MAV_RETURN_float(msg, 32);
|
---|
| 483 | }
|
---|
| 484 |
|
---|
| 485 | /**
|
---|
| 486 | * @brief Get field y_pos from control_system_state message
|
---|
| 487 | *
|
---|
| 488 | * @return Y position in local frame
|
---|
| 489 | */
|
---|
| 490 | static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg)
|
---|
| 491 | {
|
---|
| 492 | return _MAV_RETURN_float(msg, 36);
|
---|
| 493 | }
|
---|
| 494 |
|
---|
| 495 | /**
|
---|
| 496 | * @brief Get field z_pos from control_system_state message
|
---|
| 497 | *
|
---|
| 498 | * @return Z position in local frame
|
---|
| 499 | */
|
---|
| 500 | static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg)
|
---|
| 501 | {
|
---|
| 502 | return _MAV_RETURN_float(msg, 40);
|
---|
| 503 | }
|
---|
| 504 |
|
---|
| 505 | /**
|
---|
| 506 | * @brief Get field airspeed from control_system_state message
|
---|
| 507 | *
|
---|
| 508 | * @return Airspeed, set to -1 if unknown
|
---|
| 509 | */
|
---|
| 510 | static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg)
|
---|
| 511 | {
|
---|
| 512 | return _MAV_RETURN_float(msg, 44);
|
---|
| 513 | }
|
---|
| 514 |
|
---|
| 515 | /**
|
---|
| 516 | * @brief Get field vel_variance from control_system_state message
|
---|
| 517 | *
|
---|
| 518 | * @return Variance of body velocity estimate
|
---|
| 519 | */
|
---|
| 520 | static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance)
|
---|
| 521 | {
|
---|
| 522 | return _MAV_RETURN_float_array(msg, vel_variance, 3, 48);
|
---|
| 523 | }
|
---|
| 524 |
|
---|
| 525 | /**
|
---|
| 526 | * @brief Get field pos_variance from control_system_state message
|
---|
| 527 | *
|
---|
| 528 | * @return Variance in local position
|
---|
| 529 | */
|
---|
| 530 | static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance)
|
---|
| 531 | {
|
---|
| 532 | return _MAV_RETURN_float_array(msg, pos_variance, 3, 60);
|
---|
| 533 | }
|
---|
| 534 |
|
---|
| 535 | /**
|
---|
| 536 | * @brief Get field q from control_system_state message
|
---|
| 537 | *
|
---|
| 538 | * @return The attitude, represented as Quaternion
|
---|
| 539 | */
|
---|
| 540 | static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q)
|
---|
| 541 | {
|
---|
| 542 | return _MAV_RETURN_float_array(msg, q, 4, 72);
|
---|
| 543 | }
|
---|
| 544 |
|
---|
| 545 | /**
|
---|
| 546 | * @brief Get field roll_rate from control_system_state message
|
---|
| 547 | *
|
---|
| 548 | * @return Angular rate in roll axis
|
---|
| 549 | */
|
---|
| 550 | static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg)
|
---|
| 551 | {
|
---|
| 552 | return _MAV_RETURN_float(msg, 88);
|
---|
| 553 | }
|
---|
| 554 |
|
---|
| 555 | /**
|
---|
| 556 | * @brief Get field pitch_rate from control_system_state message
|
---|
| 557 | *
|
---|
| 558 | * @return Angular rate in pitch axis
|
---|
| 559 | */
|
---|
| 560 | static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg)
|
---|
| 561 | {
|
---|
| 562 | return _MAV_RETURN_float(msg, 92);
|
---|
| 563 | }
|
---|
| 564 |
|
---|
| 565 | /**
|
---|
| 566 | * @brief Get field yaw_rate from control_system_state message
|
---|
| 567 | *
|
---|
| 568 | * @return Angular rate in yaw axis
|
---|
| 569 | */
|
---|
| 570 | static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg)
|
---|
| 571 | {
|
---|
| 572 | return _MAV_RETURN_float(msg, 96);
|
---|
| 573 | }
|
---|
| 574 |
|
---|
| 575 | /**
|
---|
| 576 | * @brief Decode a control_system_state message into a struct
|
---|
| 577 | *
|
---|
| 578 | * @param msg The message to decode
|
---|
| 579 | * @param control_system_state C-struct to decode the message contents into
|
---|
| 580 | */
|
---|
| 581 | static inline void mavlink_msg_control_system_state_decode(const mavlink_message_t* msg, mavlink_control_system_state_t* control_system_state)
|
---|
| 582 | {
|
---|
| 583 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 584 | control_system_state->time_usec = mavlink_msg_control_system_state_get_time_usec(msg);
|
---|
| 585 | control_system_state->x_acc = mavlink_msg_control_system_state_get_x_acc(msg);
|
---|
| 586 | control_system_state->y_acc = mavlink_msg_control_system_state_get_y_acc(msg);
|
---|
| 587 | control_system_state->z_acc = mavlink_msg_control_system_state_get_z_acc(msg);
|
---|
| 588 | control_system_state->x_vel = mavlink_msg_control_system_state_get_x_vel(msg);
|
---|
| 589 | control_system_state->y_vel = mavlink_msg_control_system_state_get_y_vel(msg);
|
---|
| 590 | control_system_state->z_vel = mavlink_msg_control_system_state_get_z_vel(msg);
|
---|
| 591 | control_system_state->x_pos = mavlink_msg_control_system_state_get_x_pos(msg);
|
---|
| 592 | control_system_state->y_pos = mavlink_msg_control_system_state_get_y_pos(msg);
|
---|
| 593 | control_system_state->z_pos = mavlink_msg_control_system_state_get_z_pos(msg);
|
---|
| 594 | control_system_state->airspeed = mavlink_msg_control_system_state_get_airspeed(msg);
|
---|
| 595 | mavlink_msg_control_system_state_get_vel_variance(msg, control_system_state->vel_variance);
|
---|
| 596 | mavlink_msg_control_system_state_get_pos_variance(msg, control_system_state->pos_variance);
|
---|
| 597 | mavlink_msg_control_system_state_get_q(msg, control_system_state->q);
|
---|
| 598 | control_system_state->roll_rate = mavlink_msg_control_system_state_get_roll_rate(msg);
|
---|
| 599 | control_system_state->pitch_rate = mavlink_msg_control_system_state_get_pitch_rate(msg);
|
---|
| 600 | control_system_state->yaw_rate = mavlink_msg_control_system_state_get_yaw_rate(msg);
|
---|
| 601 | #else
|
---|
| 602 | uint8_t len = msg->len < MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN? msg->len : MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN;
|
---|
| 603 | memset(control_system_state, 0, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
|
---|
| 604 | memcpy(control_system_state, _MAV_PAYLOAD(msg), len);
|
---|
| 605 | #endif
|
---|
| 606 | }
|
---|