mavlink_msg_camera_trigger.h
Go to the documentation of this file.
00001 // MESSAGE CAMERA_TRIGGER PACKING
00002 
00003 #define MAVLINK_MSG_ID_CAMERA_TRIGGER 112
00004 
00005 typedef struct __mavlink_camera_trigger_t
00006 {
00007  uint64_t time_usec; /*< Timestamp for the image frame in microseconds*/
00008  uint32_t seq; /*< Image frame sequence*/
00009 } mavlink_camera_trigger_t;
00010 
00011 #define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12
00012 #define MAVLINK_MSG_ID_112_LEN 12
00013 
00014 #define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174
00015 #define MAVLINK_MSG_ID_112_CRC 174
00016 
00017 
00018 
00019 #define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \
00020         "CAMERA_TRIGGER", \
00021         2, \
00022         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \
00023          { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \
00024          } \
00025 }
00026 
00027 
00038 static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00039                                                        uint64_t time_usec, uint32_t seq)
00040 {
00041 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00042         char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN];
00043         _mav_put_uint64_t(buf, 0, time_usec);
00044         _mav_put_uint32_t(buf, 8, seq);
00045 
00046         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00047 #else
00048         mavlink_camera_trigger_t packet;
00049         packet.time_usec = time_usec;
00050         packet.seq = seq;
00051 
00052         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00053 #endif
00054 
00055         msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER;
00056 #if MAVLINK_CRC_EXTRA
00057     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
00058 #else
00059     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00060 #endif
00061 }
00062 
00073 static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00074                                                            mavlink_message_t* msg,
00075                                                            uint64_t time_usec,uint32_t seq)
00076 {
00077 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00078         char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN];
00079         _mav_put_uint64_t(buf, 0, time_usec);
00080         _mav_put_uint32_t(buf, 8, seq);
00081 
00082         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00083 #else
00084         mavlink_camera_trigger_t packet;
00085         packet.time_usec = time_usec;
00086         packet.seq = seq;
00087 
00088         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00089 #endif
00090 
00091         msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER;
00092 #if MAVLINK_CRC_EXTRA
00093     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
00094 #else
00095     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00096 #endif
00097 }
00098 
00107 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)
00108 {
00109         return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->time_usec, camera_trigger->seq);
00110 }
00111 
00121 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)
00122 {
00123         return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->time_usec, camera_trigger->seq);
00124 }
00125 
00133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00134 
00135 static inline void mavlink_msg_camera_trigger_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq)
00136 {
00137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00138         char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN];
00139         _mav_put_uint64_t(buf, 0, time_usec);
00140         _mav_put_uint32_t(buf, 8, seq);
00141 
00142 #if MAVLINK_CRC_EXTRA
00143     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
00144 #else
00145     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00146 #endif
00147 #else
00148         mavlink_camera_trigger_t packet;
00149         packet.time_usec = time_usec;
00150         packet.seq = seq;
00151 
00152 #if MAVLINK_CRC_EXTRA
00153     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
00154 #else
00155     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00156 #endif
00157 #endif
00158 }
00159 
00160 #if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00161 /*
00162   This varient of _send() can be used to save stack space by re-using
00163   memory from the receive buffer.  The caller provides a
00164   mavlink_message_t which is the size of a full mavlink message. This
00165   is usually the receive buffer for the channel, and allows a reply to an
00166   incoming message with minimum stack space usage.
00167  */
00168 static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, uint32_t seq)
00169 {
00170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00171         char *buf = (char *)msgbuf;
00172         _mav_put_uint64_t(buf, 0, time_usec);
00173         _mav_put_uint32_t(buf, 8, seq);
00174 
00175 #if MAVLINK_CRC_EXTRA
00176     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
00177 #else
00178     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00179 #endif
00180 #else
00181         mavlink_camera_trigger_t *packet = (mavlink_camera_trigger_t *)msgbuf;
00182         packet->time_usec = time_usec;
00183         packet->seq = seq;
00184 
00185 #if MAVLINK_CRC_EXTRA
00186     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
00187 #else
00188     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00189 #endif
00190 #endif
00191 }
00192 #endif
00193 
00194 #endif
00195 
00196 // MESSAGE CAMERA_TRIGGER UNPACKING
00197 
00198 
00204 static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg)
00205 {
00206         return _MAV_RETURN_uint64_t(msg,  0);
00207 }
00208 
00214 static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg)
00215 {
00216         return _MAV_RETURN_uint32_t(msg,  8);
00217 }
00218 
00225 static inline void mavlink_msg_camera_trigger_decode(const mavlink_message_t* msg, mavlink_camera_trigger_t* camera_trigger)
00226 {
00227 #if MAVLINK_NEED_BYTE_SWAP
00228         camera_trigger->time_usec = mavlink_msg_camera_trigger_get_time_usec(msg);
00229         camera_trigger->seq = mavlink_msg_camera_trigger_get_seq(msg);
00230 #else
00231         memcpy(camera_trigger, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
00232 #endif
00233 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35