mavlink_msg_terrain_request.h
Go to the documentation of this file.
00001 // MESSAGE TERRAIN_REQUEST PACKING
00002 
00003 #define MAVLINK_MSG_ID_TERRAIN_REQUEST 133
00004 
00005 typedef struct __mavlink_terrain_request_t
00006 {
00007  uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/
00008  int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/
00009  int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/
00010  uint16_t grid_spacing; /*< Grid spacing in meters*/
00011 } mavlink_terrain_request_t;
00012 
00013 #define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18
00014 #define MAVLINK_MSG_ID_133_LEN 18
00015 
00016 #define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6
00017 #define MAVLINK_MSG_ID_133_CRC 6
00018 
00019 
00020 
00021 #define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \
00022         "TERRAIN_REQUEST", \
00023         4, \
00024         {  { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \
00025          { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \
00026          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \
00027          { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \
00028          } \
00029 }
00030 
00031 
00044 static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00045                                                        int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
00046 {
00047 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00048         char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN];
00049         _mav_put_uint64_t(buf, 0, mask);
00050         _mav_put_int32_t(buf, 8, lat);
00051         _mav_put_int32_t(buf, 12, lon);
00052         _mav_put_uint16_t(buf, 16, grid_spacing);
00053 
00054         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00055 #else
00056         mavlink_terrain_request_t packet;
00057         packet.mask = mask;
00058         packet.lat = lat;
00059         packet.lon = lon;
00060         packet.grid_spacing = grid_spacing;
00061 
00062         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00063 #endif
00064 
00065         msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST;
00066 #if MAVLINK_CRC_EXTRA
00067     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
00068 #else
00069     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00070 #endif
00071 }
00072 
00085 static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00086                                                            mavlink_message_t* msg,
00087                                                            int32_t lat,int32_t lon,uint16_t grid_spacing,uint64_t mask)
00088 {
00089 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00090         char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN];
00091         _mav_put_uint64_t(buf, 0, mask);
00092         _mav_put_int32_t(buf, 8, lat);
00093         _mav_put_int32_t(buf, 12, lon);
00094         _mav_put_uint16_t(buf, 16, grid_spacing);
00095 
00096         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00097 #else
00098         mavlink_terrain_request_t packet;
00099         packet.mask = mask;
00100         packet.lat = lat;
00101         packet.lon = lon;
00102         packet.grid_spacing = grid_spacing;
00103 
00104         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00105 #endif
00106 
00107         msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST;
00108 #if MAVLINK_CRC_EXTRA
00109     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
00110 #else
00111     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00112 #endif
00113 }
00114 
00123 static inline uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request)
00124 {
00125         return mavlink_msg_terrain_request_pack(system_id, component_id, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask);
00126 }
00127 
00137 static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request)
00138 {
00139         return mavlink_msg_terrain_request_pack_chan(system_id, component_id, chan, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask);
00140 }
00141 
00151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00152 
00153 static inline void mavlink_msg_terrain_request_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
00154 {
00155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00156         char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN];
00157         _mav_put_uint64_t(buf, 0, mask);
00158         _mav_put_int32_t(buf, 8, lat);
00159         _mav_put_int32_t(buf, 12, lon);
00160         _mav_put_uint16_t(buf, 16, grid_spacing);
00161 
00162 #if MAVLINK_CRC_EXTRA
00163     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
00164 #else
00165     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00166 #endif
00167 #else
00168         mavlink_terrain_request_t packet;
00169         packet.mask = mask;
00170         packet.lat = lat;
00171         packet.lon = lon;
00172         packet.grid_spacing = grid_spacing;
00173 
00174 #if MAVLINK_CRC_EXTRA
00175     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
00176 #else
00177     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00178 #endif
00179 #endif
00180 }
00181 
00182 #if MAVLINK_MSG_ID_TERRAIN_REQUEST_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_terrain_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
00191 {
00192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00193         char *buf = (char *)msgbuf;
00194         _mav_put_uint64_t(buf, 0, mask);
00195         _mav_put_int32_t(buf, 8, lat);
00196         _mav_put_int32_t(buf, 12, lon);
00197         _mav_put_uint16_t(buf, 16, grid_spacing);
00198 
00199 #if MAVLINK_CRC_EXTRA
00200     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
00201 #else
00202     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00203 #endif
00204 #else
00205         mavlink_terrain_request_t *packet = (mavlink_terrain_request_t *)msgbuf;
00206         packet->mask = mask;
00207         packet->lat = lat;
00208         packet->lon = lon;
00209         packet->grid_spacing = grid_spacing;
00210 
00211 #if MAVLINK_CRC_EXTRA
00212     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
00213 #else
00214     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00215 #endif
00216 #endif
00217 }
00218 #endif
00219 
00220 #endif
00221 
00222 // MESSAGE TERRAIN_REQUEST UNPACKING
00223 
00224 
00230 static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg)
00231 {
00232         return _MAV_RETURN_int32_t(msg,  8);
00233 }
00234 
00240 static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg)
00241 {
00242         return _MAV_RETURN_int32_t(msg,  12);
00243 }
00244 
00250 static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg)
00251 {
00252         return _MAV_RETURN_uint16_t(msg,  16);
00253 }
00254 
00260 static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg)
00261 {
00262         return _MAV_RETURN_uint64_t(msg,  0);
00263 }
00264 
00271 static inline void mavlink_msg_terrain_request_decode(const mavlink_message_t* msg, mavlink_terrain_request_t* terrain_request)
00272 {
00273 #if MAVLINK_NEED_BYTE_SWAP
00274         terrain_request->mask = mavlink_msg_terrain_request_get_mask(msg);
00275         terrain_request->lat = mavlink_msg_terrain_request_get_lat(msg);
00276         terrain_request->lon = mavlink_msg_terrain_request_get_lon(msg);
00277         terrain_request->grid_spacing = mavlink_msg_terrain_request_get_grid_spacing(msg);
00278 #else
00279         memcpy(terrain_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
00280 #endif
00281 }


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