4#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE 154
7typedef struct __mavlink_digicam_configure_t {
9 uint16_t shutter_speed;
10 uint8_t target_system;
11 uint8_t target_component;
15 uint8_t exposure_type;
17 uint8_t engine_cut_off;
19}) mavlink_digicam_configure_t;
21#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15
22#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN 15
23#define MAVLINK_MSG_ID_154_LEN 15
24#define MAVLINK_MSG_ID_154_MIN_LEN 15
26#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC 84
27#define MAVLINK_MSG_ID_154_CRC 84
31#if MAVLINK_COMMAND_24BIT
32#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
34 "DIGICAM_CONFIGURE", \
36 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \
37 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \
38 { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \
39 { "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
40 { "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \
41 { "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \
42 { "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
43 { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \
44 { "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
45 { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \
46 { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \
50#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
51 "DIGICAM_CONFIGURE", \
53 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \
54 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \
55 { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \
56 { "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
57 { "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \
58 { "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \
59 { "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
60 { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \
61 { "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
62 { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \
63 { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \
87static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
88 uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param,
float extra_value)
90#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
91 char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
92 _mav_put_float(buf, 0, extra_value);
93 _mav_put_uint16_t(buf, 4, shutter_speed);
94 _mav_put_uint8_t(buf, 6, target_system);
95 _mav_put_uint8_t(buf, 7, target_component);
96 _mav_put_uint8_t(buf, 8, mode);
97 _mav_put_uint8_t(buf, 9, aperture);
98 _mav_put_uint8_t(buf, 10, iso);
99 _mav_put_uint8_t(buf, 11, exposure_type);
100 _mav_put_uint8_t(buf, 12, command_id);
101 _mav_put_uint8_t(buf, 13, engine_cut_off);
102 _mav_put_uint8_t(buf, 14, extra_param);
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
106 mavlink_digicam_configure_t packet;
107 packet.extra_value = extra_value;
108 packet.shutter_speed = shutter_speed;
109 packet.target_system = target_system;
110 packet.target_component = target_component;
112 packet.aperture = aperture;
114 packet.exposure_type = exposure_type;
115 packet.command_id = command_id;
116 packet.engine_cut_off = engine_cut_off;
117 packet.extra_param = extra_param;
119 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
122 msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
123 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
145static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
146 mavlink_message_t* msg,
147 uint8_t target_system,uint8_t target_component,uint8_t mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,
float extra_value)
149#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
150 char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
151 _mav_put_float(buf, 0, extra_value);
152 _mav_put_uint16_t(buf, 4, shutter_speed);
153 _mav_put_uint8_t(buf, 6, target_system);
154 _mav_put_uint8_t(buf, 7, target_component);
155 _mav_put_uint8_t(buf, 8, mode);
156 _mav_put_uint8_t(buf, 9, aperture);
157 _mav_put_uint8_t(buf, 10, iso);
158 _mav_put_uint8_t(buf, 11, exposure_type);
159 _mav_put_uint8_t(buf, 12, command_id);
160 _mav_put_uint8_t(buf, 13, engine_cut_off);
161 _mav_put_uint8_t(buf, 14, extra_param);
163 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
165 mavlink_digicam_configure_t packet;
166 packet.extra_value = extra_value;
167 packet.shutter_speed = shutter_speed;
168 packet.target_system = target_system;
169 packet.target_component = target_component;
171 packet.aperture = aperture;
173 packet.exposure_type = exposure_type;
174 packet.command_id = command_id;
175 packet.engine_cut_off = engine_cut_off;
176 packet.extra_param = extra_param;
178 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
181 msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
182 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
193static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_digicam_configure_t* digicam_configure)
195 return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
207static inline uint16_t mavlink_msg_digicam_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_digicam_configure_t* digicam_configure)
209 return mavlink_msg_digicam_configure_pack_chan(system_id, component_id, chan, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
228#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
230static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param,
float extra_value)
232#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
233 char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
234 _mav_put_float(buf, 0, extra_value);
235 _mav_put_uint16_t(buf, 4, shutter_speed);
236 _mav_put_uint8_t(buf, 6, target_system);
237 _mav_put_uint8_t(buf, 7, target_component);
238 _mav_put_uint8_t(buf, 8, mode);
239 _mav_put_uint8_t(buf, 9, aperture);
240 _mav_put_uint8_t(buf, 10, iso);
241 _mav_put_uint8_t(buf, 11, exposure_type);
242 _mav_put_uint8_t(buf, 12, command_id);
243 _mav_put_uint8_t(buf, 13, engine_cut_off);
244 _mav_put_uint8_t(buf, 14, extra_param);
246 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
248 mavlink_digicam_configure_t packet;
249 packet.extra_value = extra_value;
250 packet.shutter_speed = shutter_speed;
251 packet.target_system = target_system;
252 packet.target_component = target_component;
254 packet.aperture = aperture;
256 packet.exposure_type = exposure_type;
257 packet.command_id = command_id;
258 packet.engine_cut_off = engine_cut_off;
259 packet.extra_param = extra_param;
261 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (
const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
270static inline void mavlink_msg_digicam_configure_send_struct(mavlink_channel_t chan,
const mavlink_digicam_configure_t* digicam_configure)
272#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
273 mavlink_msg_digicam_configure_send(chan, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
275 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (
const char *)digicam_configure, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
279#if MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
287static inline void mavlink_msg_digicam_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param,
float extra_value)
289#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
290 char *buf = (
char *)msgbuf;
291 _mav_put_float(buf, 0, extra_value);
292 _mav_put_uint16_t(buf, 4, shutter_speed);
293 _mav_put_uint8_t(buf, 6, target_system);
294 _mav_put_uint8_t(buf, 7, target_component);
295 _mav_put_uint8_t(buf, 8, mode);
296 _mav_put_uint8_t(buf, 9, aperture);
297 _mav_put_uint8_t(buf, 10, iso);
298 _mav_put_uint8_t(buf, 11, exposure_type);
299 _mav_put_uint8_t(buf, 12, command_id);
300 _mav_put_uint8_t(buf, 13, engine_cut_off);
301 _mav_put_uint8_t(buf, 14, extra_param);
303 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
305 mavlink_digicam_configure_t *packet = (mavlink_digicam_configure_t *)msgbuf;
306 packet->extra_value = extra_value;
307 packet->shutter_speed = shutter_speed;
308 packet->target_system = target_system;
309 packet->target_component = target_component;
311 packet->aperture = aperture;
313 packet->exposure_type = exposure_type;
314 packet->command_id = command_id;
315 packet->engine_cut_off = engine_cut_off;
316 packet->extra_param = extra_param;
318 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (
const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
333static inline uint8_t mavlink_msg_digicam_configure_get_target_system(
const mavlink_message_t* msg)
335 return _MAV_RETURN_uint8_t(msg, 6);
343static inline uint8_t mavlink_msg_digicam_configure_get_target_component(
const mavlink_message_t* msg)
345 return _MAV_RETURN_uint8_t(msg, 7);
353static inline uint8_t mavlink_msg_digicam_configure_get_mode(
const mavlink_message_t* msg)
355 return _MAV_RETURN_uint8_t(msg, 8);
363static inline uint16_t mavlink_msg_digicam_configure_get_shutter_speed(
const mavlink_message_t* msg)
365 return _MAV_RETURN_uint16_t(msg, 4);
373static inline uint8_t mavlink_msg_digicam_configure_get_aperture(
const mavlink_message_t* msg)
375 return _MAV_RETURN_uint8_t(msg, 9);
383static inline uint8_t mavlink_msg_digicam_configure_get_iso(
const mavlink_message_t* msg)
385 return _MAV_RETURN_uint8_t(msg, 10);
393static inline uint8_t mavlink_msg_digicam_configure_get_exposure_type(
const mavlink_message_t* msg)
395 return _MAV_RETURN_uint8_t(msg, 11);
403static inline uint8_t mavlink_msg_digicam_configure_get_command_id(
const mavlink_message_t* msg)
405 return _MAV_RETURN_uint8_t(msg, 12);
413static inline uint8_t mavlink_msg_digicam_configure_get_engine_cut_off(
const mavlink_message_t* msg)
415 return _MAV_RETURN_uint8_t(msg, 13);
423static inline uint8_t mavlink_msg_digicam_configure_get_extra_param(
const mavlink_message_t* msg)
425 return _MAV_RETURN_uint8_t(msg, 14);
433static inline float mavlink_msg_digicam_configure_get_extra_value(
const mavlink_message_t* msg)
435 return _MAV_RETURN_float(msg, 0);
444static inline void mavlink_msg_digicam_configure_decode(
const mavlink_message_t* msg, mavlink_digicam_configure_t* digicam_configure)
446#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
447 digicam_configure->extra_value = mavlink_msg_digicam_configure_get_extra_value(msg);
448 digicam_configure->shutter_speed = mavlink_msg_digicam_configure_get_shutter_speed(msg);
449 digicam_configure->target_system = mavlink_msg_digicam_configure_get_target_system(msg);
450 digicam_configure->target_component = mavlink_msg_digicam_configure_get_target_component(msg);
451 digicam_configure->mode = mavlink_msg_digicam_configure_get_mode(msg);
452 digicam_configure->aperture = mavlink_msg_digicam_configure_get_aperture(msg);
453 digicam_configure->iso = mavlink_msg_digicam_configure_get_iso(msg);
454 digicam_configure->exposure_type = mavlink_msg_digicam_configure_get_exposure_type(msg);
455 digicam_configure->command_id = mavlink_msg_digicam_configure_get_command_id(msg);
456 digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg);
457 digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg);
459 uint8_t len = msg->len < MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN? msg->len : MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN;
460 memset(digicam_configure, 0, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
461 memcpy(digicam_configure, _MAV_PAYLOAD(msg), len);