4#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST 216
7typedef struct __mavlink_gopro_get_request_t {
9 uint8_t target_component;
11}) mavlink_gopro_get_request_t;
13#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN 3
14#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN 3
15#define MAVLINK_MSG_ID_216_LEN 3
16#define MAVLINK_MSG_ID_216_MIN_LEN 3
18#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC 50
19#define MAVLINK_MSG_ID_216_CRC 50
23#if MAVLINK_COMMAND_24BIT
24#define MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST { \
26 "GOPRO_GET_REQUEST", \
28 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_request_t, target_system) }, \
29 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_request_t, target_component) }, \
30 { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_get_request_t, cmd_id) }, \
34#define MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST { \
35 "GOPRO_GET_REQUEST", \
37 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_request_t, target_system) }, \
38 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_request_t, target_component) }, \
39 { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_get_request_t, cmd_id) }, \
55static inline uint16_t mavlink_msg_gopro_get_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
56 uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
58#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
59 char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
60 _mav_put_uint8_t(buf, 0, target_system);
61 _mav_put_uint8_t(buf, 1, target_component);
62 _mav_put_uint8_t(buf, 2, cmd_id);
64 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
66 mavlink_gopro_get_request_t packet;
67 packet.target_system = target_system;
68 packet.target_component = target_component;
69 packet.cmd_id = cmd_id;
71 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
74 msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_REQUEST;
75 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
89static inline uint16_t mavlink_msg_gopro_get_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
90 mavlink_message_t* msg,
91 uint8_t target_system,uint8_t target_component,uint8_t cmd_id)
93#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
95 _mav_put_uint8_t(buf, 0, target_system);
96 _mav_put_uint8_t(buf, 1, target_component);
97 _mav_put_uint8_t(buf, 2, cmd_id);
99 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
101 mavlink_gopro_get_request_t packet;
102 packet.target_system = target_system;
103 packet.target_component = target_component;
104 packet.cmd_id = cmd_id;
106 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
109 msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_REQUEST;
110 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
121static inline uint16_t mavlink_msg_gopro_get_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_gopro_get_request_t* gopro_get_request)
123 return mavlink_msg_gopro_get_request_pack(system_id, component_id, msg, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
135static inline uint16_t mavlink_msg_gopro_get_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_gopro_get_request_t* gopro_get_request)
137 return mavlink_msg_gopro_get_request_pack_chan(system_id, component_id, chan, msg, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
148#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
150static inline void mavlink_msg_gopro_get_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
152#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
153 char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
154 _mav_put_uint8_t(buf, 0, target_system);
155 _mav_put_uint8_t(buf, 1, target_component);
156 _mav_put_uint8_t(buf, 2, cmd_id);
158 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
160 mavlink_gopro_get_request_t packet;
161 packet.target_system = target_system;
162 packet.target_component = target_component;
163 packet.cmd_id = cmd_id;
165 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (
const char *)&packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
174static inline void mavlink_msg_gopro_get_request_send_struct(mavlink_channel_t chan,
const mavlink_gopro_get_request_t* gopro_get_request)
176#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
177 mavlink_msg_gopro_get_request_send(chan, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
179 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (
const char *)gopro_get_request, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
183#if MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
191static inline void mavlink_msg_gopro_get_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
193#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
194 char *buf = (
char *)msgbuf;
195 _mav_put_uint8_t(buf, 0, target_system);
196 _mav_put_uint8_t(buf, 1, target_component);
197 _mav_put_uint8_t(buf, 2, cmd_id);
199 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
201 mavlink_gopro_get_request_t *packet = (mavlink_gopro_get_request_t *)msgbuf;
202 packet->target_system = target_system;
203 packet->target_component = target_component;
204 packet->cmd_id = cmd_id;
206 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (
const char *)packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
221static inline uint8_t mavlink_msg_gopro_get_request_get_target_system(
const mavlink_message_t* msg)
223 return _MAV_RETURN_uint8_t(msg, 0);
231static inline uint8_t mavlink_msg_gopro_get_request_get_target_component(
const mavlink_message_t* msg)
233 return _MAV_RETURN_uint8_t(msg, 1);
241static inline uint8_t mavlink_msg_gopro_get_request_get_cmd_id(
const mavlink_message_t* msg)
243 return _MAV_RETURN_uint8_t(msg, 2);
252static inline void mavlink_msg_gopro_get_request_decode(
const mavlink_message_t* msg, mavlink_gopro_get_request_t* gopro_get_request)
254#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
255 gopro_get_request->target_system = mavlink_msg_gopro_get_request_get_target_system(msg);
256 gopro_get_request->target_component = mavlink_msg_gopro_get_request_get_target_component(msg);
257 gopro_get_request->cmd_id = mavlink_msg_gopro_get_request_get_cmd_id(msg);
259 uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN;
260 memset(gopro_get_request, 0, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
261 memcpy(gopro_get_request, _MAV_PAYLOAD(msg), len);