mavlink_msg_request_data_stream.h
Go to the documentation of this file.
00001 // MESSAGE REQUEST_DATA_STREAM PACKING
00002 
00003 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66
00004 
00005 typedef struct __mavlink_request_data_stream_t
00006 {
00007  uint16_t req_message_rate; /*< The requested message rate*/
00008  uint8_t target_system; /*< The target requested to send the message stream.*/
00009  uint8_t target_component; /*< The target requested to send the message stream.*/
00010  uint8_t req_stream_id; /*< The ID of the requested data stream*/
00011  uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/
00012 } mavlink_request_data_stream_t;
00013 
00014 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
00015 #define MAVLINK_MSG_ID_66_LEN 6
00016 
00017 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148
00018 #define MAVLINK_MSG_ID_66_CRC 148
00019 
00020 
00021 
00022 #define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \
00023         "REQUEST_DATA_STREAM", \
00024         5, \
00025         {  { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \
00026          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \
00027          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \
00028          { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \
00029          { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \
00030          } \
00031 }
00032 
00033 
00047 static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048                                                        uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051         char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
00052         _mav_put_uint16_t(buf, 0, req_message_rate);
00053         _mav_put_uint8_t(buf, 2, target_system);
00054         _mav_put_uint8_t(buf, 3, target_component);
00055         _mav_put_uint8_t(buf, 4, req_stream_id);
00056         _mav_put_uint8_t(buf, 5, start_stop);
00057 
00058         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00059 #else
00060         mavlink_request_data_stream_t packet;
00061         packet.req_message_rate = req_message_rate;
00062         packet.target_system = target_system;
00063         packet.target_component = target_component;
00064         packet.req_stream_id = req_stream_id;
00065         packet.start_stop = start_stop;
00066 
00067         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00068 #endif
00069 
00070         msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
00071 #if MAVLINK_CRC_EXTRA
00072     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
00073 #else
00074     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00075 #endif
00076 }
00077 
00091 static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00092                                                            mavlink_message_t* msg,
00093                                                            uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop)
00094 {
00095 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00096         char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
00097         _mav_put_uint16_t(buf, 0, req_message_rate);
00098         _mav_put_uint8_t(buf, 2, target_system);
00099         _mav_put_uint8_t(buf, 3, target_component);
00100         _mav_put_uint8_t(buf, 4, req_stream_id);
00101         _mav_put_uint8_t(buf, 5, start_stop);
00102 
00103         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00104 #else
00105         mavlink_request_data_stream_t packet;
00106         packet.req_message_rate = req_message_rate;
00107         packet.target_system = target_system;
00108         packet.target_component = target_component;
00109         packet.req_stream_id = req_stream_id;
00110         packet.start_stop = start_stop;
00111 
00112         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00113 #endif
00114 
00115         msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
00116 #if MAVLINK_CRC_EXTRA
00117     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
00118 #else
00119     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00120 #endif
00121 }
00122 
00131 static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
00132 {
00133         return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
00134 }
00135 
00145 static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
00146 {
00147         return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
00148 }
00149 
00160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00161 
00162 static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
00163 {
00164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00165         char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
00166         _mav_put_uint16_t(buf, 0, req_message_rate);
00167         _mav_put_uint8_t(buf, 2, target_system);
00168         _mav_put_uint8_t(buf, 3, target_component);
00169         _mav_put_uint8_t(buf, 4, req_stream_id);
00170         _mav_put_uint8_t(buf, 5, start_stop);
00171 
00172 #if MAVLINK_CRC_EXTRA
00173     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
00174 #else
00175     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00176 #endif
00177 #else
00178         mavlink_request_data_stream_t packet;
00179         packet.req_message_rate = req_message_rate;
00180         packet.target_system = target_system;
00181         packet.target_component = target_component;
00182         packet.req_stream_id = req_stream_id;
00183         packet.start_stop = start_stop;
00184 
00185 #if MAVLINK_CRC_EXTRA
00186     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
00187 #else
00188     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00189 #endif
00190 #endif
00191 }
00192 
00193 #if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00194 /*
00195   This varient of _send() can be used to save stack space by re-using
00196   memory from the receive buffer.  The caller provides a
00197   mavlink_message_t which is the size of a full mavlink message. This
00198   is usually the receive buffer for the channel, and allows a reply to an
00199   incoming message with minimum stack space usage.
00200  */
00201 static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
00202 {
00203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00204         char *buf = (char *)msgbuf;
00205         _mav_put_uint16_t(buf, 0, req_message_rate);
00206         _mav_put_uint8_t(buf, 2, target_system);
00207         _mav_put_uint8_t(buf, 3, target_component);
00208         _mav_put_uint8_t(buf, 4, req_stream_id);
00209         _mav_put_uint8_t(buf, 5, start_stop);
00210 
00211 #if MAVLINK_CRC_EXTRA
00212     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
00213 #else
00214     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00215 #endif
00216 #else
00217         mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf;
00218         packet->req_message_rate = req_message_rate;
00219         packet->target_system = target_system;
00220         packet->target_component = target_component;
00221         packet->req_stream_id = req_stream_id;
00222         packet->start_stop = start_stop;
00223 
00224 #if MAVLINK_CRC_EXTRA
00225     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
00226 #else
00227     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00228 #endif
00229 #endif
00230 }
00231 #endif
00232 
00233 #endif
00234 
00235 // MESSAGE REQUEST_DATA_STREAM UNPACKING
00236 
00237 
00243 static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg)
00244 {
00245         return _MAV_RETURN_uint8_t(msg,  2);
00246 }
00247 
00253 static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg)
00254 {
00255         return _MAV_RETURN_uint8_t(msg,  3);
00256 }
00257 
00263 static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
00264 {
00265         return _MAV_RETURN_uint8_t(msg,  4);
00266 }
00267 
00273 static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg)
00274 {
00275         return _MAV_RETURN_uint16_t(msg,  0);
00276 }
00277 
00283 static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg)
00284 {
00285         return _MAV_RETURN_uint8_t(msg,  5);
00286 }
00287 
00294 static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
00295 {
00296 #if MAVLINK_NEED_BYTE_SWAP
00297         request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg);
00298         request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg);
00299         request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg);
00300         request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg);
00301         request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg);
00302 #else
00303         memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
00304 #endif
00305 }


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