3 #define MAVLINK_MSG_ID_CAMERA_TRIGGER 112
11 #define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12
12 #define MAVLINK_MSG_ID_112_LEN 12
14 #define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174
15 #define MAVLINK_MSG_ID_112_CRC 174
19 #define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \
22 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \
23 { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \
38 static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39 uint64_t time_usec, uint32_t seq)
41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73 static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
74 mavlink_message_t* msg,
75 uint64_t time_usec,uint32_t seq)
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 static inline uint16_t mavlink_msg_camera_trigger_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_camera_trigger_t* camera_trigger)
109 return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->
time_usec, camera_trigger->
seq);
121 static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_camera_trigger_t* camera_trigger)
123 return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->
time_usec, camera_trigger->
seq);
133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
135 static inline void mavlink_msg_camera_trigger_send(
mavlink_channel_t chan, uint64_t time_usec, uint32_t seq)
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
142 #if MAVLINK_CRC_EXTRA
152 #if MAVLINK_CRC_EXTRA
160 #if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
168 static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t time_usec, uint32_t seq)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 char *buf = (
char *)msgbuf;
175 #if MAVLINK_CRC_EXTRA
185 #if MAVLINK_CRC_EXTRA
204 static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(
const mavlink_message_t* msg)
206 return _MAV_RETURN_uint64_t(msg, 0);
214 static inline uint32_t mavlink_msg_camera_trigger_get_seq(
const mavlink_message_t* msg)
216 return _MAV_RETURN_uint32_t(msg, 8);
225 static inline void mavlink_msg_camera_trigger_decode(
const mavlink_message_t* msg,
mavlink_camera_trigger_t* camera_trigger)
227 #if MAVLINK_NEED_BYTE_SWAP
228 camera_trigger->
time_usec = mavlink_msg_camera_trigger_get_time_usec(msg);
229 camera_trigger->
seq = mavlink_msg_camera_trigger_get_seq(msg);
struct __mavlink_camera_trigger_t mavlink_camera_trigger_t
uint64_t time_usec
Timestamp for the image frame in microseconds.
Definition: mavlink_msg_camera_trigger.h:7
Definition: mavlink_msg_camera_trigger.h:5
#define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC
Definition: mavlink_msg_camera_trigger.h:14
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 _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:143
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_CAMERA_TRIGGER
Definition: mavlink_msg_camera_trigger.h:3
#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN
Definition: mavlink_msg_camera_trigger.h:11
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
uint32_t seq
Image frame sequence.
Definition: mavlink_msg_camera_trigger.h:8
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141