mavlink_msg_terrain_report.h
Go to the documentation of this file.
00001 // MESSAGE TERRAIN_REPORT PACKING
00002 
00003 #define MAVLINK_MSG_ID_TERRAIN_REPORT 136
00004 
00005 typedef struct __mavlink_terrain_report_t
00006 {
00007  int32_t lat; /*< Latitude (degrees *10^7)*/
00008  int32_t lon; /*< Longitude (degrees *10^7)*/
00009  float terrain_height; /*< Terrain height in meters AMSL*/
00010  float current_height; /*< Current vehicle height above lat/lon terrain height (meters)*/
00011  uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/
00012  uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/
00013  uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/
00014 } mavlink_terrain_report_t;
00015 
00016 #define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22
00017 #define MAVLINK_MSG_ID_136_LEN 22
00018 
00019 #define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1
00020 #define MAVLINK_MSG_ID_136_CRC 1
00021 
00022 
00023 
00024 #define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \
00025         "TERRAIN_REPORT", \
00026         7, \
00027         {  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \
00028          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \
00029          { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \
00030          { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \
00031          { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \
00032          { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \
00033          { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \
00034          } \
00035 }
00036 
00037 
00053 static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00054                                                        int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
00055 {
00056 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00057         char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
00058         _mav_put_int32_t(buf, 0, lat);
00059         _mav_put_int32_t(buf, 4, lon);
00060         _mav_put_float(buf, 8, terrain_height);
00061         _mav_put_float(buf, 12, current_height);
00062         _mav_put_uint16_t(buf, 16, spacing);
00063         _mav_put_uint16_t(buf, 18, pending);
00064         _mav_put_uint16_t(buf, 20, loaded);
00065 
00066         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00067 #else
00068         mavlink_terrain_report_t packet;
00069         packet.lat = lat;
00070         packet.lon = lon;
00071         packet.terrain_height = terrain_height;
00072         packet.current_height = current_height;
00073         packet.spacing = spacing;
00074         packet.pending = pending;
00075         packet.loaded = loaded;
00076 
00077         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00078 #endif
00079 
00080         msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT;
00081 #if MAVLINK_CRC_EXTRA
00082     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
00083 #else
00084     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00085 #endif
00086 }
00087 
00103 static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00104                                                            mavlink_message_t* msg,
00105                                                            int32_t lat,int32_t lon,uint16_t spacing,float terrain_height,float current_height,uint16_t pending,uint16_t loaded)
00106 {
00107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00108         char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
00109         _mav_put_int32_t(buf, 0, lat);
00110         _mav_put_int32_t(buf, 4, lon);
00111         _mav_put_float(buf, 8, terrain_height);
00112         _mav_put_float(buf, 12, current_height);
00113         _mav_put_uint16_t(buf, 16, spacing);
00114         _mav_put_uint16_t(buf, 18, pending);
00115         _mav_put_uint16_t(buf, 20, loaded);
00116 
00117         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00118 #else
00119         mavlink_terrain_report_t packet;
00120         packet.lat = lat;
00121         packet.lon = lon;
00122         packet.terrain_height = terrain_height;
00123         packet.current_height = current_height;
00124         packet.spacing = spacing;
00125         packet.pending = pending;
00126         packet.loaded = loaded;
00127 
00128         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00129 #endif
00130 
00131         msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT;
00132 #if MAVLINK_CRC_EXTRA
00133     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
00134 #else
00135     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00136 #endif
00137 }
00138 
00147 static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report)
00148 {
00149         return mavlink_msg_terrain_report_pack(system_id, component_id, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded);
00150 }
00151 
00161 static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report)
00162 {
00163         return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded);
00164 }
00165 
00178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00179 
00180 static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
00181 {
00182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00183         char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
00184         _mav_put_int32_t(buf, 0, lat);
00185         _mav_put_int32_t(buf, 4, lon);
00186         _mav_put_float(buf, 8, terrain_height);
00187         _mav_put_float(buf, 12, current_height);
00188         _mav_put_uint16_t(buf, 16, spacing);
00189         _mav_put_uint16_t(buf, 18, pending);
00190         _mav_put_uint16_t(buf, 20, loaded);
00191 
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00196 #endif
00197 #else
00198         mavlink_terrain_report_t packet;
00199         packet.lat = lat;
00200         packet.lon = lon;
00201         packet.terrain_height = terrain_height;
00202         packet.current_height = current_height;
00203         packet.spacing = spacing;
00204         packet.pending = pending;
00205         packet.loaded = loaded;
00206 
00207 #if MAVLINK_CRC_EXTRA
00208     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
00209 #else
00210     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00211 #endif
00212 #endif
00213 }
00214 
00215 #if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00216 /*
00217   This varient of _send() can be used to save stack space by re-using
00218   memory from the receive buffer.  The caller provides a
00219   mavlink_message_t which is the size of a full mavlink message. This
00220   is usually the receive buffer for the channel, and allows a reply to an
00221   incoming message with minimum stack space usage.
00222  */
00223 static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
00224 {
00225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00226         char *buf = (char *)msgbuf;
00227         _mav_put_int32_t(buf, 0, lat);
00228         _mav_put_int32_t(buf, 4, lon);
00229         _mav_put_float(buf, 8, terrain_height);
00230         _mav_put_float(buf, 12, current_height);
00231         _mav_put_uint16_t(buf, 16, spacing);
00232         _mav_put_uint16_t(buf, 18, pending);
00233         _mav_put_uint16_t(buf, 20, loaded);
00234 
00235 #if MAVLINK_CRC_EXTRA
00236     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
00237 #else
00238     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00239 #endif
00240 #else
00241         mavlink_terrain_report_t *packet = (mavlink_terrain_report_t *)msgbuf;
00242         packet->lat = lat;
00243         packet->lon = lon;
00244         packet->terrain_height = terrain_height;
00245         packet->current_height = current_height;
00246         packet->spacing = spacing;
00247         packet->pending = pending;
00248         packet->loaded = loaded;
00249 
00250 #if MAVLINK_CRC_EXTRA
00251     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
00252 #else
00253     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00254 #endif
00255 #endif
00256 }
00257 #endif
00258 
00259 #endif
00260 
00261 // MESSAGE TERRAIN_REPORT UNPACKING
00262 
00263 
00269 static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg)
00270 {
00271         return _MAV_RETURN_int32_t(msg,  0);
00272 }
00273 
00279 static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg)
00280 {
00281         return _MAV_RETURN_int32_t(msg,  4);
00282 }
00283 
00289 static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg)
00290 {
00291         return _MAV_RETURN_uint16_t(msg,  16);
00292 }
00293 
00299 static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg)
00300 {
00301         return _MAV_RETURN_float(msg,  8);
00302 }
00303 
00309 static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg)
00310 {
00311         return _MAV_RETURN_float(msg,  12);
00312 }
00313 
00319 static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg)
00320 {
00321         return _MAV_RETURN_uint16_t(msg,  18);
00322 }
00323 
00329 static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg)
00330 {
00331         return _MAV_RETURN_uint16_t(msg,  20);
00332 }
00333 
00340 static inline void mavlink_msg_terrain_report_decode(const mavlink_message_t* msg, mavlink_terrain_report_t* terrain_report)
00341 {
00342 #if MAVLINK_NEED_BYTE_SWAP
00343         terrain_report->lat = mavlink_msg_terrain_report_get_lat(msg);
00344         terrain_report->lon = mavlink_msg_terrain_report_get_lon(msg);
00345         terrain_report->terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg);
00346         terrain_report->current_height = mavlink_msg_terrain_report_get_current_height(msg);
00347         terrain_report->spacing = mavlink_msg_terrain_report_get_spacing(msg);
00348         terrain_report->pending = mavlink_msg_terrain_report_get_pending(msg);
00349         terrain_report->loaded = mavlink_msg_terrain_report_get_loaded(msg);
00350 #else
00351         memcpy(terrain_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
00352 #endif
00353 }


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