Skip to content

Commit

Permalink
autogenerated headers for rev https://github.com/mavlink/mavlink/tree…
Browse files Browse the repository at this point in the history
  • Loading branch information
PX4BuildBot committed Mar 6, 2024
1 parent f21526e commit c46a23b
Show file tree
Hide file tree
Showing 448 changed files with 25,939 additions and 55 deletions.
2 changes: 1 addition & 1 deletion ASLUAV/ASLUAV.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#error Wrong include order: MAVLINK_ASLUAV.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
#endif

#define MAVLINK_ASLUAV_XML_HASH 316866643315165655
#define MAVLINK_ASLUAV_XML_HASH 5280776994826192524

#ifdef __cplusplus
extern "C" {
Expand Down
2 changes: 1 addition & 1 deletion ASLUAV/mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#ifndef MAVLINK_H
#define MAVLINK_H

#define MAVLINK_PRIMARY_XML_HASH 316866643315165655
#define MAVLINK_PRIMARY_XML_HASH 5280776994826192524

#ifndef MAVLINK_STX
#define MAVLINK_STX 253
Expand Down
68 changes: 68 additions & 0 deletions ASLUAV/mavlink_msg_asl_obctrl.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,60 @@ static inline uint16_t mavlink_msg_asl_obctrl_pack(uint8_t system_id, uint8_t co
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
}

/**
* @brief Pack a asl_obctrl message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
*
* @param timestamp [us] Time since system start
* @param uElev Elevator command [~]
* @param uThrot Throttle command [~]
* @param uThrot2 Throttle 2 command [~]
* @param uAilL Left aileron command [~]
* @param uAilR Right aileron command [~]
* @param uRud Rudder command [~]
* @param obctrl_status Off-board computer status
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_asl_obctrl_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
uint64_t timestamp, float uElev, float uThrot, float uThrot2, float uAilL, float uAilR, float uRud, uint8_t obctrl_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ASL_OBCTRL_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, uElev);
_mav_put_float(buf, 12, uThrot);
_mav_put_float(buf, 16, uThrot2);
_mav_put_float(buf, 20, uAilL);
_mav_put_float(buf, 24, uAilR);
_mav_put_float(buf, 28, uRud);
_mav_put_uint8_t(buf, 32, obctrl_status);

memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
#else
mavlink_asl_obctrl_t packet;
packet.timestamp = timestamp;
packet.uElev = uElev;
packet.uThrot = uThrot;
packet.uThrot2 = uThrot2;
packet.uAilL = uAilL;
packet.uAilR = uAilR;
packet.uRud = uRud;
packet.obctrl_status = obctrl_status;

memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
#endif

msg->msgid = MAVLINK_MSG_ID_ASL_OBCTRL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_CRC);
#else
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASL_OBCTRL_MIN_LEN, MAVLINK_MSG_ID_ASL_OBCTRL_LEN);
#endif
}

/**
* @brief Pack a asl_obctrl message on a channel
* @param system_id ID of this system
Expand Down Expand Up @@ -182,6 +236,20 @@ static inline uint16_t mavlink_msg_asl_obctrl_encode_chan(uint8_t system_id, uin
return mavlink_msg_asl_obctrl_pack_chan(system_id, component_id, chan, msg, asl_obctrl->timestamp, asl_obctrl->uElev, asl_obctrl->uThrot, asl_obctrl->uThrot2, asl_obctrl->uAilL, asl_obctrl->uAilR, asl_obctrl->uRud, asl_obctrl->obctrl_status);
}

/**
* @brief Encode a asl_obctrl struct with provided status structure
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
* @param asl_obctrl C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_asl_obctrl_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_asl_obctrl_t* asl_obctrl)
{
return mavlink_msg_asl_obctrl_pack_status(system_id, component_id, _status, msg, asl_obctrl->timestamp, asl_obctrl->uElev, asl_obctrl->uThrot, asl_obctrl->uThrot2, asl_obctrl->uAilL, asl_obctrl->uAilR, asl_obctrl->uRud, asl_obctrl->obctrl_status);
}

/**
* @brief Send a asl_obctrl message
* @param chan MAVLink channel to send the message
Expand Down
119 changes: 119 additions & 0 deletions ASLUAV/mavlink_msg_aslctrl_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,111 @@ static inline uint16_t mavlink_msg_aslctrl_data_pack(uint8_t system_id, uint8_t
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
}

/**
* @brief Pack a aslctrl_data message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
*
* @param timestamp [us] Timestamp
* @param aslctrl_mode ASLCTRL control-mode (manual, stabilized, auto, etc...)
* @param h See sourcecode for a description of these values...
* @param hRef
* @param hRef_t
* @param PitchAngle [deg] Pitch angle
* @param PitchAngleRef [deg] Pitch angle reference
* @param q
* @param qRef
* @param uElev
* @param uThrot
* @param uThrot2
* @param nZ
* @param AirspeedRef [m/s] Airspeed reference
* @param SpoilersEngaged
* @param YawAngle [deg] Yaw angle
* @param YawAngleRef [deg] Yaw angle reference
* @param RollAngle [deg] Roll angle
* @param RollAngleRef [deg] Roll angle reference
* @param p
* @param pRef
* @param r
* @param rRef
* @param uAil
* @param uRud
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_aslctrl_data_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
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 nZ, 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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ASLCTRL_DATA_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, h);
_mav_put_float(buf, 12, hRef);
_mav_put_float(buf, 16, hRef_t);
_mav_put_float(buf, 20, PitchAngle);
_mav_put_float(buf, 24, PitchAngleRef);
_mav_put_float(buf, 28, q);
_mav_put_float(buf, 32, qRef);
_mav_put_float(buf, 36, uElev);
_mav_put_float(buf, 40, uThrot);
_mav_put_float(buf, 44, uThrot2);
_mav_put_float(buf, 48, nZ);
_mav_put_float(buf, 52, AirspeedRef);
_mav_put_float(buf, 56, YawAngle);
_mav_put_float(buf, 60, YawAngleRef);
_mav_put_float(buf, 64, RollAngle);
_mav_put_float(buf, 68, RollAngleRef);
_mav_put_float(buf, 72, p);
_mav_put_float(buf, 76, pRef);
_mav_put_float(buf, 80, r);
_mav_put_float(buf, 84, rRef);
_mav_put_float(buf, 88, uAil);
_mav_put_float(buf, 92, uRud);
_mav_put_uint8_t(buf, 96, aslctrl_mode);
_mav_put_uint8_t(buf, 97, SpoilersEngaged);

memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
#else
mavlink_aslctrl_data_t packet;
packet.timestamp = timestamp;
packet.h = h;
packet.hRef = hRef;
packet.hRef_t = hRef_t;
packet.PitchAngle = PitchAngle;
packet.PitchAngleRef = PitchAngleRef;
packet.q = q;
packet.qRef = qRef;
packet.uElev = uElev;
packet.uThrot = uThrot;
packet.uThrot2 = uThrot2;
packet.nZ = nZ;
packet.AirspeedRef = AirspeedRef;
packet.YawAngle = YawAngle;
packet.YawAngleRef = YawAngleRef;
packet.RollAngle = RollAngle;
packet.RollAngleRef = RollAngleRef;
packet.p = p;
packet.pRef = pRef;
packet.r = r;
packet.rRef = rRef;
packet.uAil = uAil;
packet.uRud = uRud;
packet.aslctrl_mode = aslctrl_mode;
packet.SpoilersEngaged = SpoilersEngaged;

memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
#endif

msg->msgid = MAVLINK_MSG_ID_ASLCTRL_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
#else
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
#endif
}

/**
* @brief Pack a aslctrl_data message on a channel
* @param system_id ID of this system
Expand Down Expand Up @@ -335,6 +440,20 @@ static inline uint16_t mavlink_msg_aslctrl_data_encode_chan(uint8_t system_id, u
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->nZ, 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);
}

/**
* @brief Encode a aslctrl_data struct with provided status structure
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
* @param aslctrl_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_aslctrl_data_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_aslctrl_data_t* aslctrl_data)
{
return mavlink_msg_aslctrl_data_pack_status(system_id, component_id, _status, 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->nZ, 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);
}

/**
* @brief Send a aslctrl_data message
* @param chan MAVLink channel to send the message
Expand Down
77 changes: 77 additions & 0 deletions ASLUAV/mavlink_msg_aslctrl_debug.h
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,69 @@ static inline uint16_t mavlink_msg_aslctrl_debug_pack(uint8_t system_id, uint8_t
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ASLCTRL_DEBUG_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DEBUG_LEN, MAVLINK_MSG_ID_ASLCTRL_DEBUG_CRC);
}

/**
* @brief Pack a aslctrl_debug message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
*
* @param i32_1 Debug data
* @param i8_1 Debug data
* @param i8_2 Debug data
* @param f_1 Debug data
* @param f_2 Debug data
* @param f_3 Debug data
* @param f_4 Debug data
* @param f_5 Debug data
* @param f_6 Debug data
* @param f_7 Debug data
* @param f_8 Debug data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_aslctrl_debug_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
uint32_t i32_1, uint8_t i8_1, uint8_t i8_2, float f_1, float f_2, float f_3, float f_4, float f_5, float f_6, float f_7, float f_8)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ASLCTRL_DEBUG_LEN];
_mav_put_uint32_t(buf, 0, i32_1);
_mav_put_float(buf, 4, f_1);
_mav_put_float(buf, 8, f_2);
_mav_put_float(buf, 12, f_3);
_mav_put_float(buf, 16, f_4);
_mav_put_float(buf, 20, f_5);
_mav_put_float(buf, 24, f_6);
_mav_put_float(buf, 28, f_7);
_mav_put_float(buf, 32, f_8);
_mav_put_uint8_t(buf, 36, i8_1);
_mav_put_uint8_t(buf, 37, i8_2);

memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASLCTRL_DEBUG_LEN);
#else
mavlink_aslctrl_debug_t packet;
packet.i32_1 = i32_1;
packet.f_1 = f_1;
packet.f_2 = f_2;
packet.f_3 = f_3;
packet.f_4 = f_4;
packet.f_5 = f_5;
packet.f_6 = f_6;
packet.f_7 = f_7;
packet.f_8 = f_8;
packet.i8_1 = i8_1;
packet.i8_2 = i8_2;

memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASLCTRL_DEBUG_LEN);
#endif

msg->msgid = MAVLINK_MSG_ID_ASLCTRL_DEBUG;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASLCTRL_DEBUG_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DEBUG_LEN, MAVLINK_MSG_ID_ASLCTRL_DEBUG_CRC);
#else
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASLCTRL_DEBUG_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DEBUG_LEN);
#endif
}

/**
* @brief Pack a aslctrl_debug message on a channel
* @param system_id ID of this system
Expand Down Expand Up @@ -209,6 +272,20 @@ static inline uint16_t mavlink_msg_aslctrl_debug_encode_chan(uint8_t system_id,
return mavlink_msg_aslctrl_debug_pack_chan(system_id, component_id, chan, msg, aslctrl_debug->i32_1, aslctrl_debug->i8_1, aslctrl_debug->i8_2, aslctrl_debug->f_1, aslctrl_debug->f_2, aslctrl_debug->f_3, aslctrl_debug->f_4, aslctrl_debug->f_5, aslctrl_debug->f_6, aslctrl_debug->f_7, aslctrl_debug->f_8);
}

/**
* @brief Encode a aslctrl_debug struct with provided status structure
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
* @param aslctrl_debug C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_aslctrl_debug_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_aslctrl_debug_t* aslctrl_debug)
{
return mavlink_msg_aslctrl_debug_pack_status(system_id, component_id, _status, msg, aslctrl_debug->i32_1, aslctrl_debug->i8_1, aslctrl_debug->i8_2, aslctrl_debug->f_1, aslctrl_debug->f_2, aslctrl_debug->f_3, aslctrl_debug->f_4, aslctrl_debug->f_5, aslctrl_debug->f_6, aslctrl_debug->f_7, aslctrl_debug->f_8);
}

/**
* @brief Send a aslctrl_debug message
* @param chan MAVLink channel to send the message
Expand Down
54 changes: 54 additions & 0 deletions ASLUAV/mavlink_msg_asluav_status.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,46 @@ static inline uint16_t mavlink_msg_asluav_status_pack(uint8_t system_id, uint8_t
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ASLUAV_STATUS_MIN_LEN, MAVLINK_MSG_ID_ASLUAV_STATUS_LEN, MAVLINK_MSG_ID_ASLUAV_STATUS_CRC);
}

/**
* @brief Pack a asluav_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
*
* @param LED_status Status of the position-indicator LEDs
* @param SATCOM_status Status of the IRIDIUM satellite communication system
* @param Servo_status Status vector for up to 8 servos
* @param Motor_rpm Motor RPM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_asluav_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
uint8_t LED_status, uint8_t SATCOM_status, const uint8_t *Servo_status, float Motor_rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ASLUAV_STATUS_LEN];
_mav_put_float(buf, 0, Motor_rpm);
_mav_put_uint8_t(buf, 4, LED_status);
_mav_put_uint8_t(buf, 5, SATCOM_status);
_mav_put_uint8_t_array(buf, 6, Servo_status, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASLUAV_STATUS_LEN);
#else
mavlink_asluav_status_t packet;
packet.Motor_rpm = Motor_rpm;
packet.LED_status = LED_status;
packet.SATCOM_status = SATCOM_status;
mav_array_memcpy(packet.Servo_status, Servo_status, sizeof(uint8_t)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASLUAV_STATUS_LEN);
#endif

msg->msgid = MAVLINK_MSG_ID_ASLUAV_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASLUAV_STATUS_MIN_LEN, MAVLINK_MSG_ID_ASLUAV_STATUS_LEN, MAVLINK_MSG_ID_ASLUAV_STATUS_CRC);
#else
return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ASLUAV_STATUS_MIN_LEN, MAVLINK_MSG_ID_ASLUAV_STATUS_LEN);
#endif
}

/**
* @brief Pack a asluav_status message on a channel
* @param system_id ID of this system
Expand Down Expand Up @@ -142,6 +182,20 @@ static inline uint16_t mavlink_msg_asluav_status_encode_chan(uint8_t system_id,
return mavlink_msg_asluav_status_pack_chan(system_id, component_id, chan, msg, asluav_status->LED_status, asluav_status->SATCOM_status, asluav_status->Servo_status, asluav_status->Motor_rpm);
}

/**
* @brief Encode a asluav_status struct with provided status structure
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
* @param asluav_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_asluav_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_asluav_status_t* asluav_status)
{
return mavlink_msg_asluav_status_pack_status(system_id, component_id, _status, msg, asluav_status->LED_status, asluav_status->SATCOM_status, asluav_status->Servo_status, asluav_status->Motor_rpm);
}

/**
* @brief Send a asluav_status message
* @param chan MAVLink channel to send the message
Expand Down
Loading

0 comments on commit c46a23b

Please sign in to comment.