mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: re-generated headers
This commit is contained in:
parent
c2b4235662
commit
b052959c61
File diff suppressed because one or more lines are too long
|
@ -11,9 +11,9 @@ typedef struct __mavlink_gimbal_report_t
|
|||
float delta_velocity_x; /*< Delta velocity X (m/s)*/
|
||||
float delta_velocity_y; /*< Delta velocity Y (m/s)*/
|
||||
float delta_velocity_z; /*< Delta velocity Z (m/s)*/
|
||||
float joint_roll; /*< Joint ROLL (radians)*/
|
||||
float joint_el; /*< Joint EL (radians)*/
|
||||
float joint_az; /*< Joint AZ (radians)*/
|
||||
float joint_roll; /*< Joint ROLL (radians)*/
|
||||
float joint_el; /*< Joint EL (radians)*/
|
||||
float joint_az; /*< Joint AZ (radians)*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_report_t;
|
||||
|
@ -60,9 +60,9 @@ typedef struct __mavlink_gimbal_report_t
|
|||
* @param delta_velocity_x Delta velocity X (m/s)
|
||||
* @param delta_velocity_y Delta velocity Y (m/s)
|
||||
* @param delta_velocity_z Delta velocity Z (m/s)
|
||||
* @param joint_roll Joint ROLL (radians)
|
||||
* @param joint_el Joint EL (radians)
|
||||
* @param joint_az Joint AZ (radians)
|
||||
* @param joint_roll Joint ROLL (radians)
|
||||
* @param joint_el Joint EL (radians)
|
||||
* @param joint_az Joint AZ (radians)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
|
@ -125,9 +125,9 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
|
|||
* @param delta_velocity_x Delta velocity X (m/s)
|
||||
* @param delta_velocity_y Delta velocity Y (m/s)
|
||||
* @param delta_velocity_z Delta velocity Z (m/s)
|
||||
* @param joint_roll Joint ROLL (radians)
|
||||
* @param joint_el Joint EL (radians)
|
||||
* @param joint_az Joint AZ (radians)
|
||||
* @param joint_roll Joint ROLL (radians)
|
||||
* @param joint_el Joint EL (radians)
|
||||
* @param joint_az Joint AZ (radians)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
|
@ -216,9 +216,9 @@ static inline uint16_t mavlink_msg_gimbal_report_encode_chan(uint8_t system_id,
|
|||
* @param delta_velocity_x Delta velocity X (m/s)
|
||||
* @param delta_velocity_y Delta velocity Y (m/s)
|
||||
* @param delta_velocity_z Delta velocity Z (m/s)
|
||||
* @param joint_roll Joint ROLL (radians)
|
||||
* @param joint_el Joint EL (radians)
|
||||
* @param joint_az Joint AZ (radians)
|
||||
* @param joint_roll Joint ROLL (radians)
|
||||
* @param joint_el Joint EL (radians)
|
||||
* @param joint_az Joint AZ (radians)
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
|
@ -419,7 +419,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_velocity_z(const mavlink
|
|||
/**
|
||||
* @brief Get field joint_roll from gimbal_report message
|
||||
*
|
||||
* @return Joint ROLL (radians)
|
||||
* @return Joint ROLL (radians)
|
||||
*/
|
||||
static inline float mavlink_msg_gimbal_report_get_joint_roll(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -429,7 +429,7 @@ static inline float mavlink_msg_gimbal_report_get_joint_roll(const mavlink_messa
|
|||
/**
|
||||
* @brief Get field joint_el from gimbal_report message
|
||||
*
|
||||
* @return Joint EL (radians)
|
||||
* @return Joint EL (radians)
|
||||
*/
|
||||
static inline float mavlink_msg_gimbal_report_get_joint_el(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -439,7 +439,7 @@ static inline float mavlink_msg_gimbal_report_get_joint_el(const mavlink_message
|
|||
/**
|
||||
* @brief Get field joint_az from gimbal_report message
|
||||
*
|
||||
* @return Joint AZ (radians)
|
||||
* @return Joint AZ (radians)
|
||||
*/
|
||||
static inline float mavlink_msg_gimbal_report_get_joint_az(const mavlink_message_t* msg)
|
||||
{
|
||||
|
|
|
@ -0,0 +1,305 @@
|
|||
// MESSAGE GIMBAL_TORQUE_CMD_REPORT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT 214
|
||||
|
||||
typedef struct __mavlink_gimbal_torque_cmd_report_t
|
||||
{
|
||||
int16_t rl_torque_cmd; /*< Roll Torque Command*/
|
||||
int16_t el_torque_cmd; /*< Elevation Torque Command*/
|
||||
int16_t az_torque_cmd; /*< Azimuth Torque Command*/
|
||||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
} mavlink_gimbal_torque_cmd_report_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN 8
|
||||
#define MAVLINK_MSG_ID_214_LEN 8
|
||||
|
||||
#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC 69
|
||||
#define MAVLINK_MSG_ID_214_CRC 69
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT { \
|
||||
"GIMBAL_TORQUE_CMD_REPORT", \
|
||||
5, \
|
||||
{ { "rl_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_gimbal_torque_cmd_report_t, rl_torque_cmd) }, \
|
||||
{ "el_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_gimbal_torque_cmd_report_t, el_torque_cmd) }, \
|
||||
{ "az_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_gimbal_torque_cmd_report_t, az_torque_cmd) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_gimbal_torque_cmd_report_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_gimbal_torque_cmd_report_t, target_component) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a gimbal_torque_cmd_report 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 target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param rl_torque_cmd Roll Torque Command
|
||||
* @param el_torque_cmd Elevation Torque Command
|
||||
* @param az_torque_cmd Azimuth Torque Command
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
|
||||
_mav_put_int16_t(buf, 0, rl_torque_cmd);
|
||||
_mav_put_int16_t(buf, 2, el_torque_cmd);
|
||||
_mav_put_int16_t(buf, 4, az_torque_cmd);
|
||||
_mav_put_uint8_t(buf, 6, target_system);
|
||||
_mav_put_uint8_t(buf, 7, target_component);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#else
|
||||
mavlink_gimbal_torque_cmd_report_t packet;
|
||||
packet.rl_torque_cmd = rl_torque_cmd;
|
||||
packet.el_torque_cmd = el_torque_cmd;
|
||||
packet.az_torque_cmd = az_torque_cmd;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a gimbal_torque_cmd_report message on a channel
|
||||
* @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 will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param rl_torque_cmd Roll Torque Command
|
||||
* @param el_torque_cmd Elevation Torque Command
|
||||
* @param az_torque_cmd Azimuth Torque Command
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t target_system,uint8_t target_component,int16_t rl_torque_cmd,int16_t el_torque_cmd,int16_t az_torque_cmd)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
|
||||
_mav_put_int16_t(buf, 0, rl_torque_cmd);
|
||||
_mav_put_int16_t(buf, 2, el_torque_cmd);
|
||||
_mav_put_int16_t(buf, 4, az_torque_cmd);
|
||||
_mav_put_uint8_t(buf, 6, target_system);
|
||||
_mav_put_uint8_t(buf, 7, target_component);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#else
|
||||
mavlink_gimbal_torque_cmd_report_t packet;
|
||||
packet.rl_torque_cmd = rl_torque_cmd;
|
||||
packet.el_torque_cmd = el_torque_cmd;
|
||||
packet.az_torque_cmd = az_torque_cmd;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a gimbal_torque_cmd_report struct
|
||||
*
|
||||
* @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 gimbal_torque_cmd_report C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
|
||||
{
|
||||
return mavlink_msg_gimbal_torque_cmd_report_pack(system_id, component_id, msg, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a gimbal_torque_cmd_report struct on a channel
|
||||
*
|
||||
* @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 will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param gimbal_torque_cmd_report C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
|
||||
{
|
||||
return mavlink_msg_gimbal_torque_cmd_report_pack_chan(system_id, component_id, chan, msg, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a gimbal_torque_cmd_report message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param target_system System ID
|
||||
* @param target_component Component ID
|
||||
* @param rl_torque_cmd Roll Torque Command
|
||||
* @param el_torque_cmd Elevation Torque Command
|
||||
* @param az_torque_cmd Azimuth Torque Command
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gimbal_torque_cmd_report_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
|
||||
_mav_put_int16_t(buf, 0, rl_torque_cmd);
|
||||
_mav_put_int16_t(buf, 2, el_torque_cmd);
|
||||
_mav_put_int16_t(buf, 4, az_torque_cmd);
|
||||
_mav_put_uint8_t(buf, 6, target_system);
|
||||
_mav_put_uint8_t(buf, 7, target_component);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gimbal_torque_cmd_report_t packet;
|
||||
packet.rl_torque_cmd = rl_torque_cmd;
|
||||
packet.el_torque_cmd = el_torque_cmd;
|
||||
packet.az_torque_cmd = az_torque_cmd;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#if MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||
/*
|
||||
This varient of _send() can be used to save stack space by re-using
|
||||
memory from the receive buffer. The caller provides a
|
||||
mavlink_message_t which is the size of a full mavlink message. This
|
||||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_gimbal_torque_cmd_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_int16_t(buf, 0, rl_torque_cmd);
|
||||
_mav_put_int16_t(buf, 2, el_torque_cmd);
|
||||
_mav_put_int16_t(buf, 4, az_torque_cmd);
|
||||
_mav_put_uint8_t(buf, 6, target_system);
|
||||
_mav_put_uint8_t(buf, 7, target_component);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gimbal_torque_cmd_report_t *packet = (mavlink_gimbal_torque_cmd_report_t *)msgbuf;
|
||||
packet->rl_torque_cmd = rl_torque_cmd;
|
||||
packet->el_torque_cmd = el_torque_cmd;
|
||||
packet->az_torque_cmd = az_torque_cmd;
|
||||
packet->target_system = target_system;
|
||||
packet->target_component = target_component;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE GIMBAL_TORQUE_CMD_REPORT UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from gimbal_torque_cmd_report message
|
||||
*
|
||||
* @return System ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gimbal_torque_cmd_report_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 6);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field target_component from gimbal_torque_cmd_report message
|
||||
*
|
||||
* @return Component ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gimbal_torque_cmd_report_get_target_component(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 7);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field rl_torque_cmd from gimbal_torque_cmd_report message
|
||||
*
|
||||
* @return Roll Torque Command
|
||||
*/
|
||||
static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_rl_torque_cmd(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field el_torque_cmd from gimbal_torque_cmd_report message
|
||||
*
|
||||
* @return Elevation Torque Command
|
||||
*/
|
||||
static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_el_torque_cmd(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 2);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field az_torque_cmd from gimbal_torque_cmd_report message
|
||||
*
|
||||
* @return Azimuth Torque Command
|
||||
*/
|
||||
static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_az_torque_cmd(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a gimbal_torque_cmd_report message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param gimbal_torque_cmd_report C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_gimbal_torque_cmd_report_decode(const mavlink_message_t* msg, mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
gimbal_torque_cmd_report->rl_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_rl_torque_cmd(msg);
|
||||
gimbal_torque_cmd_report->el_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_el_torque_cmd(msg);
|
||||
gimbal_torque_cmd_report->az_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_az_torque_cmd(msg);
|
||||
gimbal_torque_cmd_report->target_system = mavlink_msg_gimbal_torque_cmd_report_get_target_system(msg);
|
||||
gimbal_torque_cmd_report->target_component = mavlink_msg_gimbal_torque_cmd_report_get_target_component(msg);
|
||||
#else
|
||||
memcpy(gimbal_torque_cmd_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
|
||||
#endif
|
||||
}
|
|
@ -5,22 +5,24 @@
|
|||
typedef struct __mavlink_gopro_get_response_t
|
||||
{
|
||||
uint8_t cmd_id; /*< Command ID*/
|
||||
uint8_t value; /*< Value*/
|
||||
uint8_t status; /*< Status*/
|
||||
uint8_t value[4]; /*< Value*/
|
||||
} mavlink_gopro_get_response_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN 2
|
||||
#define MAVLINK_MSG_ID_217_LEN 2
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC 163
|
||||
#define MAVLINK_MSG_ID_217_CRC 163
|
||||
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN 6
|
||||
#define MAVLINK_MSG_ID_217_LEN 6
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC 202
|
||||
#define MAVLINK_MSG_ID_217_CRC 202
|
||||
|
||||
#define MAVLINK_MSG_GOPRO_GET_RESPONSE_FIELD_VALUE_LEN 4
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE { \
|
||||
"GOPRO_GET_RESPONSE", \
|
||||
2, \
|
||||
3, \
|
||||
{ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_response_t, cmd_id) }, \
|
||||
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_response_t, value) }, \
|
||||
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_response_t, status) }, \
|
||||
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 2, offsetof(mavlink_gopro_get_response_t, value) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
@ -32,23 +34,24 @@ typedef struct __mavlink_gopro_get_response_t
|
|||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param cmd_id Command ID
|
||||
* @param status Status
|
||||
* @param value Value
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_get_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t cmd_id, uint8_t value)
|
||||
uint8_t cmd_id, uint8_t status, const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, value);
|
||||
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
_mav_put_uint8_t_array(buf, 2, value, 4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
|
||||
#else
|
||||
mavlink_gopro_get_response_t packet;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.value = value;
|
||||
|
||||
packet.status = status;
|
||||
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
|
||||
#endif
|
||||
|
||||
|
@ -67,24 +70,25 @@ static inline uint16_t mavlink_msg_gopro_get_response_pack(uint8_t system_id, ui
|
|||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param cmd_id Command ID
|
||||
* @param status Status
|
||||
* @param value Value
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_get_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t cmd_id,uint8_t value)
|
||||
uint8_t cmd_id,uint8_t status,const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, value);
|
||||
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
_mav_put_uint8_t_array(buf, 2, value, 4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
|
||||
#else
|
||||
mavlink_gopro_get_response_t packet;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.value = value;
|
||||
|
||||
packet.status = status;
|
||||
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
|
||||
#endif
|
||||
|
||||
|
@ -106,7 +110,7 @@ static inline uint16_t mavlink_msg_gopro_get_response_pack_chan(uint8_t system_i
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_get_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_get_response_t* gopro_get_response)
|
||||
{
|
||||
return mavlink_msg_gopro_get_response_pack(system_id, component_id, msg, gopro_get_response->cmd_id, gopro_get_response->value);
|
||||
return mavlink_msg_gopro_get_response_pack(system_id, component_id, msg, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -120,7 +124,7 @@ static inline uint16_t mavlink_msg_gopro_get_response_encode(uint8_t system_id,
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_get_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_get_response_t* gopro_get_response)
|
||||
{
|
||||
return mavlink_msg_gopro_get_response_pack_chan(system_id, component_id, chan, msg, gopro_get_response->cmd_id, gopro_get_response->value);
|
||||
return mavlink_msg_gopro_get_response_pack_chan(system_id, component_id, chan, msg, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -128,17 +132,18 @@ static inline uint16_t mavlink_msg_gopro_get_response_encode_chan(uint8_t system
|
|||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param cmd_id Command ID
|
||||
* @param status Status
|
||||
* @param value Value
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gopro_get_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t value)
|
||||
static inline void mavlink_msg_gopro_get_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t status, const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, value);
|
||||
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
_mav_put_uint8_t_array(buf, 2, value, 4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
|
||||
#else
|
||||
|
@ -147,8 +152,8 @@ static inline void mavlink_msg_gopro_get_response_send(mavlink_channel_t chan, u
|
|||
#else
|
||||
mavlink_gopro_get_response_t packet;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.value = value;
|
||||
|
||||
packet.status = status;
|
||||
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
|
||||
#else
|
||||
|
@ -165,13 +170,13 @@ static inline void mavlink_msg_gopro_get_response_send(mavlink_channel_t chan, u
|
|||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_gopro_get_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t value)
|
||||
static inline void mavlink_msg_gopro_get_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t status, const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, value);
|
||||
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
_mav_put_uint8_t_array(buf, 2, value, 4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
|
||||
#else
|
||||
|
@ -180,8 +185,8 @@ static inline void mavlink_msg_gopro_get_response_send_buf(mavlink_message_t *ms
|
|||
#else
|
||||
mavlink_gopro_get_response_t *packet = (mavlink_gopro_get_response_t *)msgbuf;
|
||||
packet->cmd_id = cmd_id;
|
||||
packet->value = value;
|
||||
|
||||
packet->status = status;
|
||||
mav_array_memcpy(packet->value, value, sizeof(uint8_t)*4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
|
||||
#else
|
||||
|
@ -206,14 +211,24 @@ static inline uint8_t mavlink_msg_gopro_get_response_get_cmd_id(const mavlink_me
|
|||
return _MAV_RETURN_uint8_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field status from gopro_get_response message
|
||||
*
|
||||
* @return Status
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gopro_get_response_get_status(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field value from gopro_get_response message
|
||||
*
|
||||
* @return Value
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gopro_get_response_get_value(const mavlink_message_t* msg)
|
||||
static inline uint16_t mavlink_msg_gopro_get_response_get_value(const mavlink_message_t* msg, uint8_t *value)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 1);
|
||||
return _MAV_RETURN_uint8_t_array(msg, value, 4, 2);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -226,7 +241,8 @@ static inline void mavlink_msg_gopro_get_response_decode(const mavlink_message_t
|
|||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
gopro_get_response->cmd_id = mavlink_msg_gopro_get_response_get_cmd_id(msg);
|
||||
gopro_get_response->value = mavlink_msg_gopro_get_response_get_value(msg);
|
||||
gopro_get_response->status = mavlink_msg_gopro_get_response_get_status(msg);
|
||||
mavlink_msg_gopro_get_response_get_value(msg, gopro_get_response->value);
|
||||
#else
|
||||
memcpy(gopro_get_response, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
|
||||
#endif
|
||||
|
|
|
@ -5,20 +5,24 @@
|
|||
typedef struct __mavlink_gopro_heartbeat_t
|
||||
{
|
||||
uint8_t status; /*< Status*/
|
||||
uint8_t capture_mode; /*< Current capture mode*/
|
||||
uint8_t flags; /*< additional status bits*/
|
||||
} mavlink_gopro_heartbeat_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN 1
|
||||
#define MAVLINK_MSG_ID_215_LEN 1
|
||||
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN 3
|
||||
#define MAVLINK_MSG_ID_215_LEN 3
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC 77
|
||||
#define MAVLINK_MSG_ID_215_CRC 77
|
||||
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC 101
|
||||
#define MAVLINK_MSG_ID_215_CRC 101
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT { \
|
||||
"GOPRO_HEARTBEAT", \
|
||||
1, \
|
||||
3, \
|
||||
{ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_heartbeat_t, status) }, \
|
||||
{ "capture_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_heartbeat_t, capture_mode) }, \
|
||||
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_heartbeat_t, flags) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
@ -30,19 +34,25 @@ typedef struct __mavlink_gopro_heartbeat_t
|
|||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param status Status
|
||||
* @param capture_mode Current capture mode
|
||||
* @param flags additional status bits
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t status)
|
||||
uint8_t status, uint8_t capture_mode, uint8_t flags)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
|
||||
_mav_put_uint8_t(buf, 0, status);
|
||||
_mav_put_uint8_t(buf, 1, capture_mode);
|
||||
_mav_put_uint8_t(buf, 2, flags);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
|
||||
#else
|
||||
mavlink_gopro_heartbeat_t packet;
|
||||
packet.status = status;
|
||||
packet.capture_mode = capture_mode;
|
||||
packet.flags = flags;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
|
||||
#endif
|
||||
|
@ -62,20 +72,26 @@ static inline uint16_t mavlink_msg_gopro_heartbeat_pack(uint8_t system_id, uint8
|
|||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param status Status
|
||||
* @param capture_mode Current capture mode
|
||||
* @param flags additional status bits
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t status)
|
||||
uint8_t status,uint8_t capture_mode,uint8_t flags)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
|
||||
_mav_put_uint8_t(buf, 0, status);
|
||||
_mav_put_uint8_t(buf, 1, capture_mode);
|
||||
_mav_put_uint8_t(buf, 2, flags);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
|
||||
#else
|
||||
mavlink_gopro_heartbeat_t packet;
|
||||
packet.status = status;
|
||||
packet.capture_mode = capture_mode;
|
||||
packet.flags = flags;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
|
||||
#endif
|
||||
|
@ -98,7 +114,7 @@ static inline uint16_t mavlink_msg_gopro_heartbeat_pack_chan(uint8_t system_id,
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
|
||||
{
|
||||
return mavlink_msg_gopro_heartbeat_pack(system_id, component_id, msg, gopro_heartbeat->status);
|
||||
return mavlink_msg_gopro_heartbeat_pack(system_id, component_id, msg, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -112,7 +128,7 @@ static inline uint16_t mavlink_msg_gopro_heartbeat_encode(uint8_t system_id, uin
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
|
||||
{
|
||||
return mavlink_msg_gopro_heartbeat_pack_chan(system_id, component_id, chan, msg, gopro_heartbeat->status);
|
||||
return mavlink_msg_gopro_heartbeat_pack_chan(system_id, component_id, chan, msg, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -120,14 +136,18 @@ static inline uint16_t mavlink_msg_gopro_heartbeat_encode_chan(uint8_t system_id
|
|||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param status Status
|
||||
* @param capture_mode Current capture mode
|
||||
* @param flags additional status bits
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gopro_heartbeat_send(mavlink_channel_t chan, uint8_t status)
|
||||
static inline void mavlink_msg_gopro_heartbeat_send(mavlink_channel_t chan, uint8_t status, uint8_t capture_mode, uint8_t flags)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
|
||||
_mav_put_uint8_t(buf, 0, status);
|
||||
_mav_put_uint8_t(buf, 1, capture_mode);
|
||||
_mav_put_uint8_t(buf, 2, flags);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
|
||||
|
@ -137,6 +157,8 @@ static inline void mavlink_msg_gopro_heartbeat_send(mavlink_channel_t chan, uint
|
|||
#else
|
||||
mavlink_gopro_heartbeat_t packet;
|
||||
packet.status = status;
|
||||
packet.capture_mode = capture_mode;
|
||||
packet.flags = flags;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
|
||||
|
@ -154,11 +176,13 @@ static inline void mavlink_msg_gopro_heartbeat_send(mavlink_channel_t chan, uint
|
|||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_gopro_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status)
|
||||
static inline void mavlink_msg_gopro_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status, uint8_t capture_mode, uint8_t flags)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint8_t(buf, 0, status);
|
||||
_mav_put_uint8_t(buf, 1, capture_mode);
|
||||
_mav_put_uint8_t(buf, 2, flags);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
|
||||
|
@ -168,6 +192,8 @@ static inline void mavlink_msg_gopro_heartbeat_send_buf(mavlink_message_t *msgbu
|
|||
#else
|
||||
mavlink_gopro_heartbeat_t *packet = (mavlink_gopro_heartbeat_t *)msgbuf;
|
||||
packet->status = status;
|
||||
packet->capture_mode = capture_mode;
|
||||
packet->flags = flags;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
|
||||
|
@ -193,6 +219,26 @@ static inline uint8_t mavlink_msg_gopro_heartbeat_get_status(const mavlink_messa
|
|||
return _MAV_RETURN_uint8_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field capture_mode from gopro_heartbeat message
|
||||
*
|
||||
* @return Current capture mode
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gopro_heartbeat_get_capture_mode(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field flags from gopro_heartbeat message
|
||||
*
|
||||
* @return additional status bits
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gopro_heartbeat_get_flags(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 2);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a gopro_heartbeat message into a struct
|
||||
*
|
||||
|
@ -203,6 +249,8 @@ static inline void mavlink_msg_gopro_heartbeat_decode(const mavlink_message_t* m
|
|||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
gopro_heartbeat->status = mavlink_msg_gopro_heartbeat_get_status(msg);
|
||||
gopro_heartbeat->capture_mode = mavlink_msg_gopro_heartbeat_get_capture_mode(msg);
|
||||
gopro_heartbeat->flags = mavlink_msg_gopro_heartbeat_get_flags(msg);
|
||||
#else
|
||||
memcpy(gopro_heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
|
||||
#endif
|
||||
|
|
|
@ -7,16 +7,16 @@ typedef struct __mavlink_gopro_set_request_t
|
|||
uint8_t target_system; /*< System ID*/
|
||||
uint8_t target_component; /*< Component ID*/
|
||||
uint8_t cmd_id; /*< Command ID*/
|
||||
uint8_t value; /*< Value*/
|
||||
uint8_t value[4]; /*< Value*/
|
||||
} mavlink_gopro_set_request_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN 4
|
||||
#define MAVLINK_MSG_ID_218_LEN 4
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC 115
|
||||
#define MAVLINK_MSG_ID_218_CRC 115
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN 7
|
||||
#define MAVLINK_MSG_ID_218_LEN 7
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC 17
|
||||
#define MAVLINK_MSG_ID_218_CRC 17
|
||||
|
||||
#define MAVLINK_MSG_GOPRO_SET_REQUEST_FIELD_VALUE_LEN 4
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST { \
|
||||
"GOPRO_SET_REQUEST", \
|
||||
|
@ -24,7 +24,7 @@ typedef struct __mavlink_gopro_set_request_t
|
|||
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_request_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_request_t, target_component) }, \
|
||||
{ "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_set_request_t, cmd_id) }, \
|
||||
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_gopro_set_request_t, value) }, \
|
||||
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 3, offsetof(mavlink_gopro_set_request_t, value) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
@ -42,23 +42,21 @@ typedef struct __mavlink_gopro_set_request_t
|
|||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_set_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t target_system, uint8_t target_component, uint8_t cmd_id, uint8_t value)
|
||||
uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
|
||||
_mav_put_uint8_t(buf, 0, target_system);
|
||||
_mav_put_uint8_t(buf, 1, target_component);
|
||||
_mav_put_uint8_t(buf, 2, cmd_id);
|
||||
_mav_put_uint8_t(buf, 3, value);
|
||||
|
||||
_mav_put_uint8_t_array(buf, 3, value, 4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
|
||||
#else
|
||||
mavlink_gopro_set_request_t packet;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.value = value;
|
||||
|
||||
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
|
||||
#endif
|
||||
|
||||
|
@ -84,23 +82,21 @@ static inline uint16_t mavlink_msg_gopro_set_request_pack(uint8_t system_id, uin
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_set_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t target_system,uint8_t target_component,uint8_t cmd_id,uint8_t value)
|
||||
uint8_t target_system,uint8_t target_component,uint8_t cmd_id,const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
|
||||
_mav_put_uint8_t(buf, 0, target_system);
|
||||
_mav_put_uint8_t(buf, 1, target_component);
|
||||
_mav_put_uint8_t(buf, 2, cmd_id);
|
||||
_mav_put_uint8_t(buf, 3, value);
|
||||
|
||||
_mav_put_uint8_t_array(buf, 3, value, 4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
|
||||
#else
|
||||
mavlink_gopro_set_request_t packet;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.value = value;
|
||||
|
||||
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
|
||||
#endif
|
||||
|
||||
|
@ -150,15 +146,14 @@ static inline uint16_t mavlink_msg_gopro_set_request_encode_chan(uint8_t system_
|
|||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gopro_set_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, uint8_t value)
|
||||
static inline void mavlink_msg_gopro_set_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
|
||||
_mav_put_uint8_t(buf, 0, target_system);
|
||||
_mav_put_uint8_t(buf, 1, target_component);
|
||||
_mav_put_uint8_t(buf, 2, cmd_id);
|
||||
_mav_put_uint8_t(buf, 3, value);
|
||||
|
||||
_mav_put_uint8_t_array(buf, 3, value, 4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
|
||||
#else
|
||||
|
@ -169,8 +164,7 @@ static inline void mavlink_msg_gopro_set_request_send(mavlink_channel_t chan, ui
|
|||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.value = value;
|
||||
|
||||
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
|
||||
#else
|
||||
|
@ -187,15 +181,14 @@ static inline void mavlink_msg_gopro_set_request_send(mavlink_channel_t chan, ui
|
|||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_gopro_set_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, uint8_t value)
|
||||
static inline void mavlink_msg_gopro_set_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint8_t(buf, 0, target_system);
|
||||
_mav_put_uint8_t(buf, 1, target_component);
|
||||
_mav_put_uint8_t(buf, 2, cmd_id);
|
||||
_mav_put_uint8_t(buf, 3, value);
|
||||
|
||||
_mav_put_uint8_t_array(buf, 3, value, 4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
|
||||
#else
|
||||
|
@ -206,8 +199,7 @@ static inline void mavlink_msg_gopro_set_request_send_buf(mavlink_message_t *msg
|
|||
packet->target_system = target_system;
|
||||
packet->target_component = target_component;
|
||||
packet->cmd_id = cmd_id;
|
||||
packet->value = value;
|
||||
|
||||
mav_array_memcpy(packet->value, value, sizeof(uint8_t)*4);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
|
||||
#else
|
||||
|
@ -257,9 +249,9 @@ static inline uint8_t mavlink_msg_gopro_set_request_get_cmd_id(const mavlink_mes
|
|||
*
|
||||
* @return Value
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gopro_set_request_get_value(const mavlink_message_t* msg)
|
||||
static inline uint16_t mavlink_msg_gopro_set_request_get_value(const mavlink_message_t* msg, uint8_t *value)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 3);
|
||||
return _MAV_RETURN_uint8_t_array(msg, value, 4, 3);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -274,7 +266,7 @@ static inline void mavlink_msg_gopro_set_request_decode(const mavlink_message_t*
|
|||
gopro_set_request->target_system = mavlink_msg_gopro_set_request_get_target_system(msg);
|
||||
gopro_set_request->target_component = mavlink_msg_gopro_set_request_get_target_component(msg);
|
||||
gopro_set_request->cmd_id = mavlink_msg_gopro_set_request_get_cmd_id(msg);
|
||||
gopro_set_request->value = mavlink_msg_gopro_set_request_get_value(msg);
|
||||
mavlink_msg_gopro_set_request_get_value(msg, gopro_set_request->value);
|
||||
#else
|
||||
memcpy(gopro_set_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
|
||||
#endif
|
||||
|
|
|
@ -5,14 +5,14 @@
|
|||
typedef struct __mavlink_gopro_set_response_t
|
||||
{
|
||||
uint8_t cmd_id; /*< Command ID*/
|
||||
uint8_t result; /*< Result*/
|
||||
uint8_t status; /*< Status*/
|
||||
} mavlink_gopro_set_response_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN 2
|
||||
#define MAVLINK_MSG_ID_219_LEN 2
|
||||
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC 47
|
||||
#define MAVLINK_MSG_ID_219_CRC 47
|
||||
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC 162
|
||||
#define MAVLINK_MSG_ID_219_CRC 162
|
||||
|
||||
|
||||
|
||||
|
@ -20,7 +20,7 @@ typedef struct __mavlink_gopro_set_response_t
|
|||
"GOPRO_SET_RESPONSE", \
|
||||
2, \
|
||||
{ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_response_t, cmd_id) }, \
|
||||
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_response_t, result) }, \
|
||||
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_response_t, status) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
@ -32,22 +32,22 @@ typedef struct __mavlink_gopro_set_response_t
|
|||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param cmd_id Command ID
|
||||
* @param result Result
|
||||
* @param status Status
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_set_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint8_t cmd_id, uint8_t result)
|
||||
uint8_t cmd_id, uint8_t status)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, result);
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
|
||||
#else
|
||||
mavlink_gopro_set_response_t packet;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.result = result;
|
||||
packet.status = status;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
|
||||
#endif
|
||||
|
@ -67,23 +67,23 @@ static inline uint16_t mavlink_msg_gopro_set_response_pack(uint8_t system_id, ui
|
|||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param cmd_id Command ID
|
||||
* @param result Result
|
||||
* @param status Status
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_set_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint8_t cmd_id,uint8_t result)
|
||||
uint8_t cmd_id,uint8_t status)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, result);
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
|
||||
#else
|
||||
mavlink_gopro_set_response_t packet;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.result = result;
|
||||
packet.status = status;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
|
||||
#endif
|
||||
|
@ -106,7 +106,7 @@ static inline uint16_t mavlink_msg_gopro_set_response_pack_chan(uint8_t system_i
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_set_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_set_response_t* gopro_set_response)
|
||||
{
|
||||
return mavlink_msg_gopro_set_response_pack(system_id, component_id, msg, gopro_set_response->cmd_id, gopro_set_response->result);
|
||||
return mavlink_msg_gopro_set_response_pack(system_id, component_id, msg, gopro_set_response->cmd_id, gopro_set_response->status);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -120,7 +120,7 @@ static inline uint16_t mavlink_msg_gopro_set_response_encode(uint8_t system_id,
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_gopro_set_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_set_response_t* gopro_set_response)
|
||||
{
|
||||
return mavlink_msg_gopro_set_response_pack_chan(system_id, component_id, chan, msg, gopro_set_response->cmd_id, gopro_set_response->result);
|
||||
return mavlink_msg_gopro_set_response_pack_chan(system_id, component_id, chan, msg, gopro_set_response->cmd_id, gopro_set_response->status);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -128,16 +128,16 @@ static inline uint16_t mavlink_msg_gopro_set_response_encode_chan(uint8_t system
|
|||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param cmd_id Command ID
|
||||
* @param result Result
|
||||
* @param status Status
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gopro_set_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t result)
|
||||
static inline void mavlink_msg_gopro_set_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t status)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, result);
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
|
||||
|
@ -147,7 +147,7 @@ static inline void mavlink_msg_gopro_set_response_send(mavlink_channel_t chan, u
|
|||
#else
|
||||
mavlink_gopro_set_response_t packet;
|
||||
packet.cmd_id = cmd_id;
|
||||
packet.result = result;
|
||||
packet.status = status;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
|
||||
|
@ -165,12 +165,12 @@ static inline void mavlink_msg_gopro_set_response_send(mavlink_channel_t chan, u
|
|||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_gopro_set_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t result)
|
||||
static inline void mavlink_msg_gopro_set_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t status)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint8_t(buf, 0, cmd_id);
|
||||
_mav_put_uint8_t(buf, 1, result);
|
||||
_mav_put_uint8_t(buf, 1, status);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
|
||||
|
@ -180,7 +180,7 @@ static inline void mavlink_msg_gopro_set_response_send_buf(mavlink_message_t *ms
|
|||
#else
|
||||
mavlink_gopro_set_response_t *packet = (mavlink_gopro_set_response_t *)msgbuf;
|
||||
packet->cmd_id = cmd_id;
|
||||
packet->result = result;
|
||||
packet->status = status;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
|
||||
|
@ -207,11 +207,11 @@ static inline uint8_t mavlink_msg_gopro_set_response_get_cmd_id(const mavlink_me
|
|||
}
|
||||
|
||||
/**
|
||||
* @brief Get field result from gopro_set_response message
|
||||
* @brief Get field status from gopro_set_response message
|
||||
*
|
||||
* @return Result
|
||||
* @return Status
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_gopro_set_response_get_result(const mavlink_message_t* msg)
|
||||
static inline uint8_t mavlink_msg_gopro_set_response_get_status(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 1);
|
||||
}
|
||||
|
@ -226,7 +226,7 @@ static inline void mavlink_msg_gopro_set_response_decode(const mavlink_message_t
|
|||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
gopro_set_response->cmd_id = mavlink_msg_gopro_set_response_get_cmd_id(msg);
|
||||
gopro_set_response->result = mavlink_msg_gopro_set_response_get_result(msg);
|
||||
gopro_set_response->status = mavlink_msg_gopro_set_response_get_status(msg);
|
||||
#else
|
||||
memcpy(gopro_set_response, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
|
||||
#endif
|
||||
|
|
|
@ -2057,34 +2057,37 @@ static void mavlink_test_gimbal_control(uint8_t system_id, uint8_t component_id,
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_reset(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
static void mavlink_test_gimbal_torque_cmd_report(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_reset_t packet_in = {
|
||||
5,72
|
||||
mavlink_gimbal_torque_cmd_report_t packet_in = {
|
||||
17235,17339,17443,151,218
|
||||
};
|
||||
mavlink_gimbal_reset_t packet1, packet2;
|
||||
mavlink_gimbal_torque_cmd_report_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.rl_torque_cmd = packet_in.rl_torque_cmd;
|
||||
packet1.el_torque_cmd = packet_in.el_torque_cmd;
|
||||
packet1.az_torque_cmd = packet_in.az_torque_cmd;
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_reset_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_reset_decode(&msg, &packet2);
|
||||
mavlink_msg_gimbal_torque_cmd_report_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_torque_cmd_report_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_reset_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_reset_decode(&msg, &packet2);
|
||||
mavlink_msg_gimbal_torque_cmd_report_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.rl_torque_cmd , packet1.el_torque_cmd , packet1.az_torque_cmd );
|
||||
mavlink_msg_gimbal_torque_cmd_report_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_reset_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_reset_decode(&msg, &packet2);
|
||||
mavlink_msg_gimbal_torque_cmd_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.rl_torque_cmd , packet1.el_torque_cmd , packet1.az_torque_cmd );
|
||||
mavlink_msg_gimbal_torque_cmd_report_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
|
@ -2092,511 +2095,12 @@ static void mavlink_test_gimbal_reset(uint8_t system_id, uint8_t component_id, m
|
|||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_reset_decode(last_msg, &packet2);
|
||||
mavlink_msg_gimbal_torque_cmd_report_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_reset_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_reset_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_axis_calibration_progress(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_axis_calibration_progress_t packet_in = {
|
||||
5,72,139
|
||||
};
|
||||
mavlink_gimbal_axis_calibration_progress_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.calibration_axis = packet_in.calibration_axis;
|
||||
packet1.calibration_progress = packet_in.calibration_progress;
|
||||
packet1.calibration_status = packet_in.calibration_status;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_axis_calibration_progress_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_axis_calibration_progress_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_axis_calibration_progress_pack(system_id, component_id, &msg , packet1.calibration_axis , packet1.calibration_progress , packet1.calibration_status );
|
||||
mavlink_msg_gimbal_axis_calibration_progress_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_axis_calibration_progress_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.calibration_axis , packet1.calibration_progress , packet1.calibration_status );
|
||||
mavlink_msg_gimbal_axis_calibration_progress_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_axis_calibration_progress_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_axis_calibration_progress_send(MAVLINK_COMM_1 , packet1.calibration_axis , packet1.calibration_progress , packet1.calibration_status );
|
||||
mavlink_msg_gimbal_axis_calibration_progress_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_set_home_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_set_home_offsets_t packet_in = {
|
||||
5,72
|
||||
};
|
||||
mavlink_gimbal_set_home_offsets_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_home_offsets_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_set_home_offsets_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_home_offsets_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_set_home_offsets_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_home_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_set_home_offsets_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_set_home_offsets_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_home_offsets_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_set_home_offsets_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_home_offset_calibration_result(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_home_offset_calibration_result_t packet_in = {
|
||||
5
|
||||
};
|
||||
mavlink_gimbal_home_offset_calibration_result_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.calibration_result = packet_in.calibration_result;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_pack(system_id, component_id, &msg , packet1.calibration_result );
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.calibration_result );
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_send(MAVLINK_COMM_1 , packet1.calibration_result );
|
||||
mavlink_msg_gimbal_home_offset_calibration_result_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_set_factory_parameters(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_set_factory_parameters_t packet_in = {
|
||||
963497464,963497672,963497880,963498088,963498296,963498504,18483,211,22,89,156,223,34,101
|
||||
};
|
||||
mavlink_gimbal_set_factory_parameters_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.magic_1 = packet_in.magic_1;
|
||||
packet1.magic_2 = packet_in.magic_2;
|
||||
packet1.magic_3 = packet_in.magic_3;
|
||||
packet1.serial_number_pt_1 = packet_in.serial_number_pt_1;
|
||||
packet1.serial_number_pt_2 = packet_in.serial_number_pt_2;
|
||||
packet1.serial_number_pt_3 = packet_in.serial_number_pt_3;
|
||||
packet1.assembly_year = packet_in.assembly_year;
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
packet1.assembly_month = packet_in.assembly_month;
|
||||
packet1.assembly_day = packet_in.assembly_day;
|
||||
packet1.assembly_hour = packet_in.assembly_hour;
|
||||
packet1.assembly_minute = packet_in.assembly_minute;
|
||||
packet1.assembly_second = packet_in.assembly_second;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_factory_parameters_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_set_factory_parameters_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_factory_parameters_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.magic_1 , packet1.magic_2 , packet1.magic_3 , packet1.assembly_year , packet1.assembly_month , packet1.assembly_day , packet1.assembly_hour , packet1.assembly_minute , packet1.assembly_second , packet1.serial_number_pt_1 , packet1.serial_number_pt_2 , packet1.serial_number_pt_3 );
|
||||
mavlink_msg_gimbal_set_factory_parameters_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_factory_parameters_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.magic_1 , packet1.magic_2 , packet1.magic_3 , packet1.assembly_year , packet1.assembly_month , packet1.assembly_day , packet1.assembly_hour , packet1.assembly_minute , packet1.assembly_second , packet1.serial_number_pt_1 , packet1.serial_number_pt_2 , packet1.serial_number_pt_3 );
|
||||
mavlink_msg_gimbal_set_factory_parameters_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_set_factory_parameters_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_set_factory_parameters_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.magic_1 , packet1.magic_2 , packet1.magic_3 , packet1.assembly_year , packet1.assembly_month , packet1.assembly_day , packet1.assembly_hour , packet1.assembly_minute , packet1.assembly_second , packet1.serial_number_pt_1 , packet1.serial_number_pt_2 , packet1.serial_number_pt_3 );
|
||||
mavlink_msg_gimbal_set_factory_parameters_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_factory_parameters_loaded(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_factory_parameters_loaded_t packet_in = {
|
||||
5
|
||||
};
|
||||
mavlink_gimbal_factory_parameters_loaded_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.dummy = packet_in.dummy;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_pack(system_id, component_id, &msg , packet1.dummy );
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.dummy );
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_send(MAVLINK_COMM_1 , packet1.dummy );
|
||||
mavlink_msg_gimbal_factory_parameters_loaded_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_erase_firmware_and_config(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_erase_firmware_and_config_t packet_in = {
|
||||
963497464,17,84
|
||||
};
|
||||
mavlink_gimbal_erase_firmware_and_config_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.knock = packet_in.knock;
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.knock );
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.knock );
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.knock );
|
||||
mavlink_msg_gimbal_erase_firmware_and_config_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_perform_factory_tests(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_perform_factory_tests_t packet_in = {
|
||||
5,72
|
||||
};
|
||||
mavlink_gimbal_perform_factory_tests_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_perform_factory_tests_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_perform_factory_tests_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_perform_factory_tests_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_perform_factory_tests_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_perform_factory_tests_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_perform_factory_tests_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_perform_factory_tests_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_perform_factory_tests_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_perform_factory_tests_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_report_factory_tests_progress(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_report_factory_tests_progress_t packet_in = {
|
||||
5,72,139,206
|
||||
};
|
||||
mavlink_gimbal_report_factory_tests_progress_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.test = packet_in.test;
|
||||
packet1.test_section = packet_in.test_section;
|
||||
packet1.test_section_progress = packet_in.test_section_progress;
|
||||
packet1.test_status = packet_in.test_status;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_pack(system_id, component_id, &msg , packet1.test , packet1.test_section , packet1.test_section_progress , packet1.test_status );
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.test , packet1.test_section , packet1.test_section_progress , packet1.test_status );
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_send(MAVLINK_COMM_1 , packet1.test , packet1.test_section , packet1.test_section_progress , packet1.test_status );
|
||||
mavlink_msg_gimbal_report_factory_tests_progress_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_request_axis_calibration_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_request_axis_calibration_status_t packet_in = {
|
||||
5,72
|
||||
};
|
||||
mavlink_gimbal_request_axis_calibration_status_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_request_axis_calibration_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_report_axis_calibration_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_report_axis_calibration_status_t packet_in = {
|
||||
5,72,139
|
||||
};
|
||||
mavlink_gimbal_report_axis_calibration_status_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.yaw_requires_calibration = packet_in.yaw_requires_calibration;
|
||||
packet1.pitch_requires_calibration = packet_in.pitch_requires_calibration;
|
||||
packet1.roll_requires_calibration = packet_in.roll_requires_calibration;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_pack(system_id, component_id, &msg , packet1.yaw_requires_calibration , packet1.pitch_requires_calibration , packet1.roll_requires_calibration );
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.yaw_requires_calibration , packet1.pitch_requires_calibration , packet1.roll_requires_calibration );
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_send(MAVLINK_COMM_1 , packet1.yaw_requires_calibration , packet1.pitch_requires_calibration , packet1.roll_requires_calibration );
|
||||
mavlink_msg_gimbal_report_axis_calibration_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_gimbal_request_axis_calibration(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gimbal_request_axis_calibration_t packet_in = {
|
||||
5,72
|
||||
};
|
||||
mavlink_gimbal_request_axis_calibration_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_gimbal_request_axis_calibration_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_request_axis_calibration_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_request_axis_calibration_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_gimbal_request_axis_calibration_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gimbal_request_axis_calibration_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
|
||||
mavlink_msg_gimbal_request_axis_calibration_decode(last_msg, &packet2);
|
||||
mavlink_msg_gimbal_torque_cmd_report_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.rl_torque_cmd , packet1.el_torque_cmd , packet1.az_torque_cmd );
|
||||
mavlink_msg_gimbal_torque_cmd_report_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
|
@ -2606,11 +2110,13 @@ static void mavlink_test_gopro_heartbeat(uint8_t system_id, uint8_t component_id
|
|||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gopro_heartbeat_t packet_in = {
|
||||
5
|
||||
5,72,139
|
||||
};
|
||||
mavlink_gopro_heartbeat_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.status = packet_in.status;
|
||||
packet1.capture_mode = packet_in.capture_mode;
|
||||
packet1.flags = packet_in.flags;
|
||||
|
||||
|
||||
|
||||
|
@ -2620,12 +2126,12 @@ static void mavlink_test_gopro_heartbeat(uint8_t system_id, uint8_t component_id
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_heartbeat_pack(system_id, component_id, &msg , packet1.status );
|
||||
mavlink_msg_gopro_heartbeat_pack(system_id, component_id, &msg , packet1.status , packet1.capture_mode , packet1.flags );
|
||||
mavlink_msg_gopro_heartbeat_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status );
|
||||
mavlink_msg_gopro_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status , packet1.capture_mode , packet1.flags );
|
||||
mavlink_msg_gopro_heartbeat_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
|
@ -2638,7 +2144,7 @@ static void mavlink_test_gopro_heartbeat(uint8_t system_id, uint8_t component_id
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_heartbeat_send(MAVLINK_COMM_1 , packet1.status );
|
||||
mavlink_msg_gopro_heartbeat_send(MAVLINK_COMM_1 , packet1.status , packet1.capture_mode , packet1.flags );
|
||||
mavlink_msg_gopro_heartbeat_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
@ -2694,13 +2200,14 @@ static void mavlink_test_gopro_get_response(uint8_t system_id, uint8_t component
|
|||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gopro_get_response_t packet_in = {
|
||||
5,72
|
||||
5,72,{ 139, 140, 141, 142 }
|
||||
};
|
||||
mavlink_gopro_get_response_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.cmd_id = packet_in.cmd_id;
|
||||
packet1.value = packet_in.value;
|
||||
packet1.status = packet_in.status;
|
||||
|
||||
mav_array_memcpy(packet1.value, packet_in.value, sizeof(uint8_t)*4);
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
|
@ -2709,12 +2216,12 @@ static void mavlink_test_gopro_get_response(uint8_t system_id, uint8_t component
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_get_response_pack(system_id, component_id, &msg , packet1.cmd_id , packet1.value );
|
||||
mavlink_msg_gopro_get_response_pack(system_id, component_id, &msg , packet1.cmd_id , packet1.status , packet1.value );
|
||||
mavlink_msg_gopro_get_response_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_get_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cmd_id , packet1.value );
|
||||
mavlink_msg_gopro_get_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cmd_id , packet1.status , packet1.value );
|
||||
mavlink_msg_gopro_get_response_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
|
@ -2727,7 +2234,7 @@ static void mavlink_test_gopro_get_response(uint8_t system_id, uint8_t component
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_get_response_send(MAVLINK_COMM_1 , packet1.cmd_id , packet1.value );
|
||||
mavlink_msg_gopro_get_response_send(MAVLINK_COMM_1 , packet1.cmd_id , packet1.status , packet1.value );
|
||||
mavlink_msg_gopro_get_response_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
@ -2738,15 +2245,15 @@ static void mavlink_test_gopro_set_request(uint8_t system_id, uint8_t component_
|
|||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_gopro_set_request_t packet_in = {
|
||||
5,72,139,206
|
||||
5,72,139,{ 206, 207, 208, 209 }
|
||||
};
|
||||
mavlink_gopro_set_request_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.target_system = packet_in.target_system;
|
||||
packet1.target_component = packet_in.target_component;
|
||||
packet1.cmd_id = packet_in.cmd_id;
|
||||
packet1.value = packet_in.value;
|
||||
|
||||
mav_array_memcpy(packet1.value, packet_in.value, sizeof(uint8_t)*4);
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
|
@ -2789,7 +2296,7 @@ static void mavlink_test_gopro_set_response(uint8_t system_id, uint8_t component
|
|||
mavlink_gopro_set_response_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.cmd_id = packet_in.cmd_id;
|
||||
packet1.result = packet_in.result;
|
||||
packet1.status = packet_in.status;
|
||||
|
||||
|
||||
|
||||
|
@ -2799,12 +2306,12 @@ static void mavlink_test_gopro_set_response(uint8_t system_id, uint8_t component
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_set_response_pack(system_id, component_id, &msg , packet1.cmd_id , packet1.result );
|
||||
mavlink_msg_gopro_set_response_pack(system_id, component_id, &msg , packet1.cmd_id , packet1.status );
|
||||
mavlink_msg_gopro_set_response_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_set_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cmd_id , packet1.result );
|
||||
mavlink_msg_gopro_set_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cmd_id , packet1.status );
|
||||
mavlink_msg_gopro_set_response_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
|
@ -2817,7 +2324,7 @@ static void mavlink_test_gopro_set_response(uint8_t system_id, uint8_t component
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_gopro_set_response_send(MAVLINK_COMM_1 , packet1.cmd_id , packet1.result );
|
||||
mavlink_msg_gopro_set_response_send(MAVLINK_COMM_1 , packet1.cmd_id , packet1.status );
|
||||
mavlink_msg_gopro_set_response_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
@ -2910,18 +2417,7 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
|
|||
mavlink_test_pid_tuning(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_report(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_control(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_reset(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_axis_calibration_progress(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_set_home_offsets(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_home_offset_calibration_result(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_set_factory_parameters(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_factory_parameters_loaded(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_erase_firmware_and_config(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_perform_factory_tests(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_report_factory_tests_progress(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_request_axis_calibration_status(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_report_axis_calibration_status(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_request_axis_calibration(system_id, component_id, last_msg);
|
||||
mavlink_test_gimbal_torque_cmd_report(system_id, component_id, last_msg);
|
||||
mavlink_test_gopro_heartbeat(system_id, component_id, last_msg);
|
||||
mavlink_test_gopro_get_request(system_id, component_id, last_msg);
|
||||
mavlink_test_gopro_get_response(system_id, component_id, last_msg);
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Tue Dec 15 12:18:37 2015"
|
||||
#define MAVLINK_BUILD_DATE "Sat Jan 2 08:44:07 2016"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Tue Dec 15 12:18:39 2015"
|
||||
#define MAVLINK_BUILD_DATE "Sat Jan 2 08:44:09 2016"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
Loading…
Reference in New Issue