mavlink_msg_raw_pressure.h
Go to the documentation of this file.
00001 // MESSAGE RAW_PRESSURE PACKING
00002 
00003 #define MAVLINK_MSG_ID_RAW_PRESSURE 28
00004 
00005 typedef struct __mavlink_raw_pressure_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
00008  int16_t press_abs; /*< Absolute pressure (raw)*/
00009  int16_t press_diff1; /*< Differential pressure 1 (raw)*/
00010  int16_t press_diff2; /*< Differential pressure 2 (raw)*/
00011  int16_t temperature; /*< Raw Temperature measurement (raw)*/
00012 } mavlink_raw_pressure_t;
00013 
00014 #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
00015 #define MAVLINK_MSG_ID_28_LEN 16
00016 
00017 #define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67
00018 #define MAVLINK_MSG_ID_28_CRC 67
00019 
00020 
00021 
00022 #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
00023         "RAW_PRESSURE", \
00024         5, \
00025         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
00026          { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
00027          { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
00028          { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
00029          { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
00030          } \
00031 }
00032 
00033 
00047 static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048                                                        uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051         char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
00052         _mav_put_uint64_t(buf, 0, time_usec);
00053         _mav_put_int16_t(buf, 8, press_abs);
00054         _mav_put_int16_t(buf, 10, press_diff1);
00055         _mav_put_int16_t(buf, 12, press_diff2);
00056         _mav_put_int16_t(buf, 14, temperature);
00057 
00058         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00059 #else
00060         mavlink_raw_pressure_t packet;
00061         packet.time_usec = time_usec;
00062         packet.press_abs = press_abs;
00063         packet.press_diff1 = press_diff1;
00064         packet.press_diff2 = press_diff2;
00065         packet.temperature = temperature;
00066 
00067         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00068 #endif
00069 
00070         msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
00071 #if MAVLINK_CRC_EXTRA
00072     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
00073 #else
00074     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00075 #endif
00076 }
00077 
00091 static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00092                                                            mavlink_message_t* msg,
00093                                                            uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature)
00094 {
00095 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00096         char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
00097         _mav_put_uint64_t(buf, 0, time_usec);
00098         _mav_put_int16_t(buf, 8, press_abs);
00099         _mav_put_int16_t(buf, 10, press_diff1);
00100         _mav_put_int16_t(buf, 12, press_diff2);
00101         _mav_put_int16_t(buf, 14, temperature);
00102 
00103         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00104 #else
00105         mavlink_raw_pressure_t packet;
00106         packet.time_usec = time_usec;
00107         packet.press_abs = press_abs;
00108         packet.press_diff1 = press_diff1;
00109         packet.press_diff2 = press_diff2;
00110         packet.temperature = temperature;
00111 
00112         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00113 #endif
00114 
00115         msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
00116 #if MAVLINK_CRC_EXTRA
00117     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
00118 #else
00119     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00120 #endif
00121 }
00122 
00131 static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
00132 {
00133         return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
00134 }
00135 
00145 static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
00146 {
00147         return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
00148 }
00149 
00160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00161 
00162 static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
00163 {
00164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00165         char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
00166         _mav_put_uint64_t(buf, 0, time_usec);
00167         _mav_put_int16_t(buf, 8, press_abs);
00168         _mav_put_int16_t(buf, 10, press_diff1);
00169         _mav_put_int16_t(buf, 12, press_diff2);
00170         _mav_put_int16_t(buf, 14, temperature);
00171 
00172 #if MAVLINK_CRC_EXTRA
00173     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
00174 #else
00175     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00176 #endif
00177 #else
00178         mavlink_raw_pressure_t packet;
00179         packet.time_usec = time_usec;
00180         packet.press_abs = press_abs;
00181         packet.press_diff1 = press_diff1;
00182         packet.press_diff2 = press_diff2;
00183         packet.temperature = temperature;
00184 
00185 #if MAVLINK_CRC_EXTRA
00186     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
00187 #else
00188     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00189 #endif
00190 #endif
00191 }
00192 
00193 #if MAVLINK_MSG_ID_RAW_PRESSURE_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_raw_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
00202 {
00203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00204         char *buf = (char *)msgbuf;
00205         _mav_put_uint64_t(buf, 0, time_usec);
00206         _mav_put_int16_t(buf, 8, press_abs);
00207         _mav_put_int16_t(buf, 10, press_diff1);
00208         _mav_put_int16_t(buf, 12, press_diff2);
00209         _mav_put_int16_t(buf, 14, temperature);
00210 
00211 #if MAVLINK_CRC_EXTRA
00212     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
00213 #else
00214     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00215 #endif
00216 #else
00217         mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf;
00218         packet->time_usec = time_usec;
00219         packet->press_abs = press_abs;
00220         packet->press_diff1 = press_diff1;
00221         packet->press_diff2 = press_diff2;
00222         packet->temperature = temperature;
00223 
00224 #if MAVLINK_CRC_EXTRA
00225     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
00226 #else
00227     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00228 #endif
00229 #endif
00230 }
00231 #endif
00232 
00233 #endif
00234 
00235 // MESSAGE RAW_PRESSURE UNPACKING
00236 
00237 
00243 static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg)
00244 {
00245         return _MAV_RETURN_uint64_t(msg,  0);
00246 }
00247 
00253 static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
00254 {
00255         return _MAV_RETURN_int16_t(msg,  8);
00256 }
00257 
00263 static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
00264 {
00265         return _MAV_RETURN_int16_t(msg,  10);
00266 }
00267 
00273 static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
00274 {
00275         return _MAV_RETURN_int16_t(msg,  12);
00276 }
00277 
00283 static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
00284 {
00285         return _MAV_RETURN_int16_t(msg,  14);
00286 }
00287 
00294 static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
00295 {
00296 #if MAVLINK_NEED_BYTE_SWAP
00297         raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg);
00298         raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
00299         raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
00300         raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
00301         raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg);
00302 #else
00303         memcpy(raw_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
00304 #endif
00305 }


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