mavlink_msg_terrain_data.h
Go to the documentation of this file.
00001 // MESSAGE TERRAIN_DATA PACKING
00002 
00003 #define MAVLINK_MSG_ID_TERRAIN_DATA 134
00004 
00005 typedef struct __mavlink_terrain_data_t
00006 {
00007  int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/
00008  int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/
00009  uint16_t grid_spacing; /*< Grid spacing in meters*/
00010  int16_t data[16]; /*< Terrain data in meters AMSL*/
00011  uint8_t gridbit; /*< bit within the terrain request mask*/
00012 } mavlink_terrain_data_t;
00013 
00014 #define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43
00015 #define MAVLINK_MSG_ID_134_LEN 43
00016 
00017 #define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229
00018 #define MAVLINK_MSG_ID_134_CRC 229
00019 
00020 #define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16
00021 
00022 #define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \
00023         "TERRAIN_DATA", \
00024         5, \
00025         {  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \
00026          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \
00027          { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \
00028          { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \
00029          { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \
00030          } \
00031 }
00032 
00033 
00047 static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048                                                        int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051         char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
00052         _mav_put_int32_t(buf, 0, lat);
00053         _mav_put_int32_t(buf, 4, lon);
00054         _mav_put_uint16_t(buf, 8, grid_spacing);
00055         _mav_put_uint8_t(buf, 42, gridbit);
00056         _mav_put_int16_t_array(buf, 10, data, 16);
00057         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00058 #else
00059         mavlink_terrain_data_t packet;
00060         packet.lat = lat;
00061         packet.lon = lon;
00062         packet.grid_spacing = grid_spacing;
00063         packet.gridbit = gridbit;
00064         mav_array_memcpy(packet.data, data, sizeof(int16_t)*16);
00065         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00066 #endif
00067 
00068         msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
00069 #if MAVLINK_CRC_EXTRA
00070     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
00071 #else
00072     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00073 #endif
00074 }
00075 
00089 static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00090                                                            mavlink_message_t* msg,
00091                                                            int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,const int16_t *data)
00092 {
00093 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00094         char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
00095         _mav_put_int32_t(buf, 0, lat);
00096         _mav_put_int32_t(buf, 4, lon);
00097         _mav_put_uint16_t(buf, 8, grid_spacing);
00098         _mav_put_uint8_t(buf, 42, gridbit);
00099         _mav_put_int16_t_array(buf, 10, data, 16);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00101 #else
00102         mavlink_terrain_data_t packet;
00103         packet.lat = lat;
00104         packet.lon = lon;
00105         packet.grid_spacing = grid_spacing;
00106         packet.gridbit = gridbit;
00107         mav_array_memcpy(packet.data, data, sizeof(int16_t)*16);
00108         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00109 #endif
00110 
00111         msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
00112 #if MAVLINK_CRC_EXTRA
00113     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
00114 #else
00115     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00116 #endif
00117 }
00118 
00127 static inline uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data)
00128 {
00129         return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data);
00130 }
00131 
00141 static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data)
00142 {
00143         return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data);
00144 }
00145 
00156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00157 
00158 static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
00159 {
00160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00161         char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
00162         _mav_put_int32_t(buf, 0, lat);
00163         _mav_put_int32_t(buf, 4, lon);
00164         _mav_put_uint16_t(buf, 8, grid_spacing);
00165         _mav_put_uint8_t(buf, 42, gridbit);
00166         _mav_put_int16_t_array(buf, 10, data, 16);
00167 #if MAVLINK_CRC_EXTRA
00168     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
00169 #else
00170     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00171 #endif
00172 #else
00173         mavlink_terrain_data_t packet;
00174         packet.lat = lat;
00175         packet.lon = lon;
00176         packet.grid_spacing = grid_spacing;
00177         packet.gridbit = gridbit;
00178         mav_array_memcpy(packet.data, data, sizeof(int16_t)*16);
00179 #if MAVLINK_CRC_EXTRA
00180     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
00181 #else
00182     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00183 #endif
00184 #endif
00185 }
00186 
00187 #if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00188 /*
00189   This varient of _send() can be used to save stack space by re-using
00190   memory from the receive buffer.  The caller provides a
00191   mavlink_message_t which is the size of a full mavlink message. This
00192   is usually the receive buffer for the channel, and allows a reply to an
00193   incoming message with minimum stack space usage.
00194  */
00195 static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
00196 {
00197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00198         char *buf = (char *)msgbuf;
00199         _mav_put_int32_t(buf, 0, lat);
00200         _mav_put_int32_t(buf, 4, lon);
00201         _mav_put_uint16_t(buf, 8, grid_spacing);
00202         _mav_put_uint8_t(buf, 42, gridbit);
00203         _mav_put_int16_t_array(buf, 10, data, 16);
00204 #if MAVLINK_CRC_EXTRA
00205     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
00206 #else
00207     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00208 #endif
00209 #else
00210         mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf;
00211         packet->lat = lat;
00212         packet->lon = lon;
00213         packet->grid_spacing = grid_spacing;
00214         packet->gridbit = gridbit;
00215         mav_array_memcpy(packet->data, data, sizeof(int16_t)*16);
00216 #if MAVLINK_CRC_EXTRA
00217     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
00218 #else
00219     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00220 #endif
00221 #endif
00222 }
00223 #endif
00224 
00225 #endif
00226 
00227 // MESSAGE TERRAIN_DATA UNPACKING
00228 
00229 
00235 static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg)
00236 {
00237         return _MAV_RETURN_int32_t(msg,  0);
00238 }
00239 
00245 static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg)
00246 {
00247         return _MAV_RETURN_int32_t(msg,  4);
00248 }
00249 
00255 static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg)
00256 {
00257         return _MAV_RETURN_uint16_t(msg,  8);
00258 }
00259 
00265 static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg)
00266 {
00267         return _MAV_RETURN_uint8_t(msg,  42);
00268 }
00269 
00275 static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data)
00276 {
00277         return _MAV_RETURN_int16_t_array(msg, data, 16,  10);
00278 }
00279 
00286 static inline void mavlink_msg_terrain_data_decode(const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data)
00287 {
00288 #if MAVLINK_NEED_BYTE_SWAP
00289         terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg);
00290         terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg);
00291         terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg);
00292         mavlink_msg_terrain_data_get_data(msg, terrain_data->data);
00293         terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg);
00294 #else
00295         memcpy(terrain_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
00296 #endif
00297 }


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