3 #define MAVLINK_MSG_ID_ASLCTRL_DATA 203
34 #define MAVLINK_MSG_ID_ASLCTRL_DATA_LEN 98
35 #define MAVLINK_MSG_ID_203_LEN 98
37 #define MAVLINK_MSG_ID_ASLCTRL_DATA_CRC 0
38 #define MAVLINK_MSG_ID_203_CRC 0
42 #define MAVLINK_MESSAGE_INFO_ASLCTRL_DATA { \
45 { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_aslctrl_data_t, timestamp) }, \
46 { "h", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aslctrl_data_t, h) }, \
47 { "hRef", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aslctrl_data_t, hRef) }, \
48 { "hRef_t", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_aslctrl_data_t, hRef_t) }, \
49 { "PitchAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_aslctrl_data_t, PitchAngle) }, \
50 { "PitchAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_aslctrl_data_t, PitchAngleRef) }, \
51 { "q", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_aslctrl_data_t, q) }, \
52 { "qRef", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_aslctrl_data_t, qRef) }, \
53 { "uElev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_aslctrl_data_t, uElev) }, \
54 { "uThrot", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_aslctrl_data_t, uThrot) }, \
55 { "uThrot2", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_aslctrl_data_t, uThrot2) }, \
56 { "aZ", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_aslctrl_data_t, aZ) }, \
57 { "AirspeedRef", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_aslctrl_data_t, AirspeedRef) }, \
58 { "YawAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_aslctrl_data_t, YawAngle) }, \
59 { "YawAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_aslctrl_data_t, YawAngleRef) }, \
60 { "RollAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_aslctrl_data_t, RollAngle) }, \
61 { "RollAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_aslctrl_data_t, RollAngleRef) }, \
62 { "p", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_aslctrl_data_t, p) }, \
63 { "pRef", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_aslctrl_data_t, pRef) }, \
64 { "r", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_aslctrl_data_t, r) }, \
65 { "rRef", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_aslctrl_data_t, rRef) }, \
66 { "uAil", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_aslctrl_data_t, uAil) }, \
67 { "uRud", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_aslctrl_data_t, uRud) }, \
68 { "aslctrl_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 96, offsetof(mavlink_aslctrl_data_t, aslctrl_mode) }, \
69 { "SpoilersEngaged", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_aslctrl_data_t, SpoilersEngaged) }, \
107 static inline uint16_t mavlink_msg_aslctrl_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
108 uint64_t timestamp, uint8_t aslctrl_mode,
float h,
float hRef,
float hRef_t,
float PitchAngle,
float PitchAngleRef,
float q,
float qRef,
float uElev,
float uThrot,
float uThrot2,
float aZ,
float AirspeedRef, uint8_t SpoilersEngaged,
float YawAngle,
float YawAngleRef,
float RollAngle,
float RollAngleRef,
float p,
float pRef,
float r,
float rRef,
float uAil,
float uRud)
110 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149 packet.
uElev = uElev;
171 #if MAVLINK_CRC_EXTRA
211 static inline uint16_t mavlink_msg_aslctrl_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
212 mavlink_message_t* msg,
213 uint64_t timestamp,uint8_t aslctrl_mode,
float h,
float hRef,
float hRef_t,
float PitchAngle,
float PitchAngleRef,
float q,
float qRef,
float uElev,
float uThrot,
float uThrot2,
float aZ,
float AirspeedRef,uint8_t SpoilersEngaged,
float YawAngle,
float YawAngleRef,
float RollAngle,
float RollAngleRef,
float p,
float pRef,
float r,
float rRef,
float uAil,
float uRud)
215 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
254 packet.
uElev = uElev;
276 #if MAVLINK_CRC_EXTRA
291 static inline uint16_t mavlink_msg_aslctrl_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_aslctrl_data_t* aslctrl_data)
293 return mavlink_msg_aslctrl_data_pack(system_id, component_id, msg, aslctrl_data->
timestamp, aslctrl_data->
aslctrl_mode, aslctrl_data->
h, aslctrl_data->
hRef, aslctrl_data->
hRef_t, aslctrl_data->
PitchAngle, aslctrl_data->
PitchAngleRef, aslctrl_data->
q, aslctrl_data->
qRef, aslctrl_data->
uElev, aslctrl_data->
uThrot, aslctrl_data->
uThrot2, aslctrl_data->
aZ, aslctrl_data->
AirspeedRef, aslctrl_data->
SpoilersEngaged, aslctrl_data->
YawAngle, aslctrl_data->
YawAngleRef, aslctrl_data->
RollAngle, aslctrl_data->
RollAngleRef, aslctrl_data->
p, aslctrl_data->
pRef, aslctrl_data->
r, aslctrl_data->
rRef, aslctrl_data->
uAil, aslctrl_data->
uRud);
305 static inline uint16_t mavlink_msg_aslctrl_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_aslctrl_data_t* aslctrl_data)
307 return mavlink_msg_aslctrl_data_pack_chan(system_id, component_id, chan, msg, aslctrl_data->
timestamp, aslctrl_data->
aslctrl_mode, aslctrl_data->
h, aslctrl_data->
hRef, aslctrl_data->
hRef_t, aslctrl_data->
PitchAngle, aslctrl_data->
PitchAngleRef, aslctrl_data->
q, aslctrl_data->
qRef, aslctrl_data->
uElev, aslctrl_data->
uThrot, aslctrl_data->
uThrot2, aslctrl_data->
aZ, aslctrl_data->
AirspeedRef, aslctrl_data->
SpoilersEngaged, aslctrl_data->
YawAngle, aslctrl_data->
YawAngleRef, aslctrl_data->
RollAngle, aslctrl_data->
RollAngleRef, aslctrl_data->
p, aslctrl_data->
pRef, aslctrl_data->
r, aslctrl_data->
rRef, aslctrl_data->
uAil, aslctrl_data->
uRud);
340 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
342 static inline void mavlink_msg_aslctrl_data_send(
mavlink_channel_t chan, uint64_t timestamp, uint8_t aslctrl_mode,
float h,
float hRef,
float hRef_t,
float PitchAngle,
float PitchAngleRef,
float q,
float qRef,
float uElev,
float uThrot,
float uThrot2,
float aZ,
float AirspeedRef, uint8_t SpoilersEngaged,
float YawAngle,
float YawAngleRef,
float RollAngle,
float RollAngleRef,
float p,
float pRef,
float r,
float rRef,
float uAil,
float uRud)
344 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
372 #if MAVLINK_CRC_EXTRA
387 packet.
uElev = uElev;
405 #if MAVLINK_CRC_EXTRA
413 #if MAVLINK_MSG_ID_ASLCTRL_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
421 static inline void mavlink_msg_aslctrl_data_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t timestamp, uint8_t aslctrl_mode,
float h,
float hRef,
float hRef_t,
float PitchAngle,
float PitchAngleRef,
float q,
float qRef,
float uElev,
float uThrot,
float uThrot2,
float aZ,
float AirspeedRef, uint8_t SpoilersEngaged,
float YawAngle,
float YawAngleRef,
float RollAngle,
float RollAngleRef,
float p,
float pRef,
float r,
float rRef,
float uAil,
float uRud)
423 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
424 char *buf = (
char *)msgbuf;
451 #if MAVLINK_CRC_EXTRA
466 packet->
uElev = uElev;
484 #if MAVLINK_CRC_EXTRA
503 static inline uint64_t mavlink_msg_aslctrl_data_get_timestamp(
const mavlink_message_t* msg)
505 return _MAV_RETURN_uint64_t(msg, 0);
513 static inline uint8_t mavlink_msg_aslctrl_data_get_aslctrl_mode(
const mavlink_message_t* msg)
523 static inline float mavlink_msg_aslctrl_data_get_h(
const mavlink_message_t* msg)
525 return _MAV_RETURN_float(msg, 8);
533 static inline float mavlink_msg_aslctrl_data_get_hRef(
const mavlink_message_t* msg)
535 return _MAV_RETURN_float(msg, 12);
543 static inline float mavlink_msg_aslctrl_data_get_hRef_t(
const mavlink_message_t* msg)
545 return _MAV_RETURN_float(msg, 16);
553 static inline float mavlink_msg_aslctrl_data_get_PitchAngle(
const mavlink_message_t* msg)
555 return _MAV_RETURN_float(msg, 20);
563 static inline float mavlink_msg_aslctrl_data_get_PitchAngleRef(
const mavlink_message_t* msg)
565 return _MAV_RETURN_float(msg, 24);
573 static inline float mavlink_msg_aslctrl_data_get_q(
const mavlink_message_t* msg)
575 return _MAV_RETURN_float(msg, 28);
583 static inline float mavlink_msg_aslctrl_data_get_qRef(
const mavlink_message_t* msg)
585 return _MAV_RETURN_float(msg, 32);
593 static inline float mavlink_msg_aslctrl_data_get_uElev(
const mavlink_message_t* msg)
595 return _MAV_RETURN_float(msg, 36);
603 static inline float mavlink_msg_aslctrl_data_get_uThrot(
const mavlink_message_t* msg)
605 return _MAV_RETURN_float(msg, 40);
613 static inline float mavlink_msg_aslctrl_data_get_uThrot2(
const mavlink_message_t* msg)
615 return _MAV_RETURN_float(msg, 44);
623 static inline float mavlink_msg_aslctrl_data_get_aZ(
const mavlink_message_t* msg)
625 return _MAV_RETURN_float(msg, 48);
633 static inline float mavlink_msg_aslctrl_data_get_AirspeedRef(
const mavlink_message_t* msg)
635 return _MAV_RETURN_float(msg, 52);
643 static inline uint8_t mavlink_msg_aslctrl_data_get_SpoilersEngaged(
const mavlink_message_t* msg)
653 static inline float mavlink_msg_aslctrl_data_get_YawAngle(
const mavlink_message_t* msg)
655 return _MAV_RETURN_float(msg, 56);
663 static inline float mavlink_msg_aslctrl_data_get_YawAngleRef(
const mavlink_message_t* msg)
665 return _MAV_RETURN_float(msg, 60);
673 static inline float mavlink_msg_aslctrl_data_get_RollAngle(
const mavlink_message_t* msg)
675 return _MAV_RETURN_float(msg, 64);
683 static inline float mavlink_msg_aslctrl_data_get_RollAngleRef(
const mavlink_message_t* msg)
685 return _MAV_RETURN_float(msg, 68);
693 static inline float mavlink_msg_aslctrl_data_get_p(
const mavlink_message_t* msg)
695 return _MAV_RETURN_float(msg, 72);
703 static inline float mavlink_msg_aslctrl_data_get_pRef(
const mavlink_message_t* msg)
705 return _MAV_RETURN_float(msg, 76);
713 static inline float mavlink_msg_aslctrl_data_get_r(
const mavlink_message_t* msg)
715 return _MAV_RETURN_float(msg, 80);
723 static inline float mavlink_msg_aslctrl_data_get_rRef(
const mavlink_message_t* msg)
725 return _MAV_RETURN_float(msg, 84);
733 static inline float mavlink_msg_aslctrl_data_get_uAil(
const mavlink_message_t* msg)
735 return _MAV_RETURN_float(msg, 88);
743 static inline float mavlink_msg_aslctrl_data_get_uRud(
const mavlink_message_t* msg)
745 return _MAV_RETURN_float(msg, 92);
754 static inline void mavlink_msg_aslctrl_data_decode(
const mavlink_message_t* msg,
mavlink_aslctrl_data_t* aslctrl_data)
756 #if MAVLINK_NEED_BYTE_SWAP
757 aslctrl_data->
timestamp = mavlink_msg_aslctrl_data_get_timestamp(msg);
758 aslctrl_data->
h = mavlink_msg_aslctrl_data_get_h(msg);
759 aslctrl_data->
hRef = mavlink_msg_aslctrl_data_get_hRef(msg);
760 aslctrl_data->
hRef_t = mavlink_msg_aslctrl_data_get_hRef_t(msg);
761 aslctrl_data->
PitchAngle = mavlink_msg_aslctrl_data_get_PitchAngle(msg);
762 aslctrl_data->
PitchAngleRef = mavlink_msg_aslctrl_data_get_PitchAngleRef(msg);
763 aslctrl_data->
q = mavlink_msg_aslctrl_data_get_q(msg);
764 aslctrl_data->
qRef = mavlink_msg_aslctrl_data_get_qRef(msg);
765 aslctrl_data->
uElev = mavlink_msg_aslctrl_data_get_uElev(msg);
766 aslctrl_data->
uThrot = mavlink_msg_aslctrl_data_get_uThrot(msg);
767 aslctrl_data->
uThrot2 = mavlink_msg_aslctrl_data_get_uThrot2(msg);
768 aslctrl_data->
aZ = mavlink_msg_aslctrl_data_get_aZ(msg);
769 aslctrl_data->
AirspeedRef = mavlink_msg_aslctrl_data_get_AirspeedRef(msg);
770 aslctrl_data->
YawAngle = mavlink_msg_aslctrl_data_get_YawAngle(msg);
771 aslctrl_data->
YawAngleRef = mavlink_msg_aslctrl_data_get_YawAngleRef(msg);
772 aslctrl_data->
RollAngle = mavlink_msg_aslctrl_data_get_RollAngle(msg);
773 aslctrl_data->
RollAngleRef = mavlink_msg_aslctrl_data_get_RollAngleRef(msg);
774 aslctrl_data->
p = mavlink_msg_aslctrl_data_get_p(msg);
775 aslctrl_data->
pRef = mavlink_msg_aslctrl_data_get_pRef(msg);
776 aslctrl_data->
r = mavlink_msg_aslctrl_data_get_r(msg);
777 aslctrl_data->
rRef = mavlink_msg_aslctrl_data_get_rRef(msg);
778 aslctrl_data->
uAil = mavlink_msg_aslctrl_data_get_uAil(msg);
779 aslctrl_data->
uRud = mavlink_msg_aslctrl_data_get_uRud(msg);
780 aslctrl_data->
aslctrl_mode = mavlink_msg_aslctrl_data_get_aslctrl_mode(msg);
781 aslctrl_data->
SpoilersEngaged = mavlink_msg_aslctrl_data_get_SpoilersEngaged(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float PitchAngleRef
Pitch angle reference[deg].
Definition: mavlink_msg_aslctrl_data.h:12
float uAil
Definition: mavlink_msg_aslctrl_data.h:28
uint64_t timestamp
Timestamp.
Definition: mavlink_msg_aslctrl_data.h:7
float YawAngle
Yaw angle [deg].
Definition: mavlink_msg_aslctrl_data.h:20
float aZ
Definition: mavlink_msg_aslctrl_data.h:18
float rRef
Definition: mavlink_msg_aslctrl_data.h:27
#define MAVLINK_MSG_ID_ASLCTRL_DATA_CRC
Definition: mavlink_msg_aslctrl_data.h:37
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
uint8_t aslctrl_mode
ASLCTRL control-mode (manual, stabilized, auto, etc...)
Definition: mavlink_msg_aslctrl_data.h:30
float YawAngleRef
Yaw angle reference[deg].
Definition: mavlink_msg_aslctrl_data.h:21
float qRef
Definition: mavlink_msg_aslctrl_data.h:14
float h
See sourcecode for a description of these values...
Definition: mavlink_msg_aslctrl_data.h:8
struct __mavlink_aslctrl_data_t mavlink_aslctrl_data_t
float AirspeedRef
Airspeed reference [m/s].
Definition: mavlink_msg_aslctrl_data.h:19
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.
Definition: mavlink_helpers.h:105
float pRef
Definition: mavlink_msg_aslctrl_data.h:25
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:143
float uElev
Definition: mavlink_msg_aslctrl_data.h:15
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
float uThrot2
Definition: mavlink_msg_aslctrl_data.h:17
float uThrot
Definition: mavlink_msg_aslctrl_data.h:16
float r
Definition: mavlink_msg_aslctrl_data.h:26
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float hRef_t
Definition: mavlink_msg_aslctrl_data.h:10
float p
Definition: mavlink_msg_aslctrl_data.h:24
float uRud
Definition: mavlink_msg_aslctrl_data.h:29
Definition: mavlink_msg_aslctrl_data.h:5
float RollAngle
Roll angle [deg].
Definition: mavlink_msg_aslctrl_data.h:22
float q
Definition: mavlink_msg_aslctrl_data.h:13
float hRef
Definition: mavlink_msg_aslctrl_data.h:9
float RollAngleRef
Roll angle reference[deg].
Definition: mavlink_msg_aslctrl_data.h:23
uint8_t SpoilersEngaged
Definition: mavlink_msg_aslctrl_data.h:31
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.
Definition: mavlink_helpers.h:71
#define MAVLINK_MSG_ID_ASLCTRL_DATA
Definition: mavlink_msg_aslctrl_data.h:3
#define MAVLINK_MSG_ID_ASLCTRL_DATA_LEN
Definition: mavlink_msg_aslctrl_data.h:34
float PitchAngle
Pitch angle [deg].
Definition: mavlink_msg_aslctrl_data.h:11