3 #define MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED 207
10 #define MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED_LEN 1
11 #define MAVLINK_MSG_ID_207_LEN 1
13 #define MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED_CRC 201
14 #define MAVLINK_MSG_ID_207_CRC 201
18 #define MAVLINK_MESSAGE_INFO_GIMBAL_FACTORY_PARAMETERS_LOADED { \
19 "GIMBAL_FACTORY_PARAMETERS_LOADED", \
21 { { "dummy", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gimbal_factory_parameters_loaded_t, dummy) }, \
35 static inline uint16_t mavlink_msg_gimbal_factory_parameters_loaded_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
38 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 static inline uint16_t mavlink_msg_gimbal_factory_parameters_loaded_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
68 mavlink_message_t* msg,
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
99 static inline uint16_t mavlink_msg_gimbal_factory_parameters_loaded_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_gimbal_factory_parameters_loaded_t* gimbal_factory_parameters_loaded)
101 return mavlink_msg_gimbal_factory_parameters_loaded_pack(system_id, component_id, msg, gimbal_factory_parameters_loaded->
dummy);
113 static inline uint16_t mavlink_msg_gimbal_factory_parameters_loaded_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_gimbal_factory_parameters_loaded_t* gimbal_factory_parameters_loaded)
115 return mavlink_msg_gimbal_factory_parameters_loaded_pack_chan(system_id, component_id, chan, msg, gimbal_factory_parameters_loaded->
dummy);
124 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
126 static inline void mavlink_msg_gimbal_factory_parameters_loaded_send(
mavlink_channel_t chan, uint8_t dummy)
128 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 #if MAVLINK_CRC_EXTRA
139 packet.
dummy = dummy;
141 #if MAVLINK_CRC_EXTRA
149 #if MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
157 static inline void mavlink_msg_gimbal_factory_parameters_loaded_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t dummy)
159 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
160 char *buf = (
char *)msgbuf;
163 #if MAVLINK_CRC_EXTRA
170 packet->
dummy = dummy;
172 #if MAVLINK_CRC_EXTRA
191 static inline uint8_t mavlink_msg_gimbal_factory_parameters_loaded_get_dummy(
const mavlink_message_t* msg)
204 #if MAVLINK_NEED_BYTE_SWAP
205 gimbal_factory_parameters_loaded->
dummy = mavlink_msg_gimbal_factory_parameters_loaded_get_dummy(msg);
struct __mavlink_gimbal_factory_parameters_loaded_t mavlink_gimbal_factory_parameters_loaded_t
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED_LEN
Definition: mavlink_msg_gimbal_factory_parameters_loaded.h:10
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED
Definition: mavlink_msg_gimbal_factory_parameters_loaded.h:3
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
Definition: mavlink_msg_gimbal_factory_parameters_loaded.h:5
#define MAVLINK_MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED_CRC
Definition: mavlink_msg_gimbal_factory_parameters_loaded.h:13
uint8_t dummy
Dummy field because mavgen doesn't allow messages with no fields.
Definition: mavlink_msg_gimbal_factory_parameters_loaded.h:7
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71