mavlink_msg_mission_request_partial_list.h
Go to the documentation of this file.
00001 // MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING
00002 
00003 #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37
00004 
00005 typedef struct __mavlink_mission_request_partial_list_t
00006 {
00007  int16_t start_index; /*< Start index, 0 by default*/
00008  int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/
00009  uint8_t target_system; /*< System ID*/
00010  uint8_t target_component; /*< Component ID*/
00011 } mavlink_mission_request_partial_list_t;
00012 
00013 #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6
00014 #define MAVLINK_MSG_ID_37_LEN 6
00015 
00016 #define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212
00017 #define MAVLINK_MSG_ID_37_CRC 212
00018 
00019 
00020 
00021 #define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \
00022         "MISSION_REQUEST_PARTIAL_LIST", \
00023         4, \
00024         {  { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \
00025          { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \
00026          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \
00027          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \
00028          } \
00029 }
00030 
00031 
00044 static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00045                                                        uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
00046 {
00047 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00048         char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
00049         _mav_put_int16_t(buf, 0, start_index);
00050         _mav_put_int16_t(buf, 2, end_index);
00051         _mav_put_uint8_t(buf, 4, target_system);
00052         _mav_put_uint8_t(buf, 5, target_component);
00053 
00054         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00055 #else
00056         mavlink_mission_request_partial_list_t packet;
00057         packet.start_index = start_index;
00058         packet.end_index = end_index;
00059         packet.target_system = target_system;
00060         packet.target_component = target_component;
00061 
00062         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00063 #endif
00064 
00065         msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST;
00066 #if MAVLINK_CRC_EXTRA
00067     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
00068 #else
00069     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00070 #endif
00071 }
00072 
00085 static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00086                                                            mavlink_message_t* msg,
00087                                                            uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index)
00088 {
00089 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00090         char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
00091         _mav_put_int16_t(buf, 0, start_index);
00092         _mav_put_int16_t(buf, 2, end_index);
00093         _mav_put_uint8_t(buf, 4, target_system);
00094         _mav_put_uint8_t(buf, 5, target_component);
00095 
00096         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00097 #else
00098         mavlink_mission_request_partial_list_t packet;
00099         packet.start_index = start_index;
00100         packet.end_index = end_index;
00101         packet.target_system = target_system;
00102         packet.target_component = target_component;
00103 
00104         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00105 #endif
00106 
00107         msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST;
00108 #if MAVLINK_CRC_EXTRA
00109     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
00110 #else
00111     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00112 #endif
00113 }
00114 
00123 static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list)
00124 {
00125         return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index);
00126 }
00127 
00137 static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list)
00138 {
00139         return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index);
00140 }
00141 
00151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00152 
00153 static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
00154 {
00155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00156         char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
00157         _mav_put_int16_t(buf, 0, start_index);
00158         _mav_put_int16_t(buf, 2, end_index);
00159         _mav_put_uint8_t(buf, 4, target_system);
00160         _mav_put_uint8_t(buf, 5, target_component);
00161 
00162 #if MAVLINK_CRC_EXTRA
00163     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
00164 #else
00165     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00166 #endif
00167 #else
00168         mavlink_mission_request_partial_list_t packet;
00169         packet.start_index = start_index;
00170         packet.end_index = end_index;
00171         packet.target_system = target_system;
00172         packet.target_component = target_component;
00173 
00174 #if MAVLINK_CRC_EXTRA
00175     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
00176 #else
00177     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00178 #endif
00179 #endif
00180 }
00181 
00182 #if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00183 /*
00184   This varient of _send() can be used to save stack space by re-using
00185   memory from the receive buffer.  The caller provides a
00186   mavlink_message_t which is the size of a full mavlink message. This
00187   is usually the receive buffer for the channel, and allows a reply to an
00188   incoming message with minimum stack space usage.
00189  */
00190 static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
00191 {
00192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00193         char *buf = (char *)msgbuf;
00194         _mav_put_int16_t(buf, 0, start_index);
00195         _mav_put_int16_t(buf, 2, end_index);
00196         _mav_put_uint8_t(buf, 4, target_system);
00197         _mav_put_uint8_t(buf, 5, target_component);
00198 
00199 #if MAVLINK_CRC_EXTRA
00200     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
00201 #else
00202     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00203 #endif
00204 #else
00205         mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf;
00206         packet->start_index = start_index;
00207         packet->end_index = end_index;
00208         packet->target_system = target_system;
00209         packet->target_component = target_component;
00210 
00211 #if MAVLINK_CRC_EXTRA
00212     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
00213 #else
00214     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00215 #endif
00216 #endif
00217 }
00218 #endif
00219 
00220 #endif
00221 
00222 // MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING
00223 
00224 
00230 static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg)
00231 {
00232         return _MAV_RETURN_uint8_t(msg,  4);
00233 }
00234 
00240 static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg)
00241 {
00242         return _MAV_RETURN_uint8_t(msg,  5);
00243 }
00244 
00250 static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg)
00251 {
00252         return _MAV_RETURN_int16_t(msg,  0);
00253 }
00254 
00260 static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg)
00261 {
00262         return _MAV_RETURN_int16_t(msg,  2);
00263 }
00264 
00271 static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list)
00272 {
00273 #if MAVLINK_NEED_BYTE_SWAP
00274         mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg);
00275         mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg);
00276         mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg);
00277         mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg);
00278 #else
00279         memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
00280 #endif
00281 }


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