2
0

mavlink_msg_raw_pressure.h 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372
  1. #pragma once
  2. // MESSAGE RAW_PRESSURE PACKING
  3. #define MAVLINK_MSG_ID_RAW_PRESSURE 28
  4. typedef struct __mavlink_raw_pressure_t {
  5. uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
  6. int16_t press_abs; /*< Absolute pressure (raw)*/
  7. int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistent)*/
  8. int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistent)*/
  9. int16_t temperature; /*< Raw Temperature measurement (raw)*/
  10. } mavlink_raw_pressure_t;
  11. #define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
  12. #define MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN 16
  13. #define MAVLINK_MSG_ID_28_LEN 16
  14. #define MAVLINK_MSG_ID_28_MIN_LEN 16
  15. #define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67
  16. #define MAVLINK_MSG_ID_28_CRC 67
  17. #if MAVLINK_COMMAND_24BIT
  18. #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
  19. 28, \
  20. "RAW_PRESSURE", \
  21. 5, \
  22. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
  23. { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
  24. { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
  25. { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
  26. { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
  27. } \
  28. }
  29. #else
  30. #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
  31. "RAW_PRESSURE", \
  32. 5, \
  33. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
  34. { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
  35. { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
  36. { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
  37. { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
  38. } \
  39. }
  40. #endif
  41. /**
  42. * @brief Pack a raw_pressure message
  43. * @param system_id ID of this system
  44. * @param component_id ID of this component (e.g. 200 for IMU)
  45. * @param msg The MAVLink message to compress the data into
  46. *
  47. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  48. * @param press_abs Absolute pressure (raw)
  49. * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
  50. * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
  51. * @param temperature Raw Temperature measurement (raw)
  52. * @return length of the message in bytes (excluding serial stream start sign)
  53. */
  54. static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  55. uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
  56. {
  57. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  58. char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
  59. _mav_put_uint64_t(buf, 0, time_usec);
  60. _mav_put_int16_t(buf, 8, press_abs);
  61. _mav_put_int16_t(buf, 10, press_diff1);
  62. _mav_put_int16_t(buf, 12, press_diff2);
  63. _mav_put_int16_t(buf, 14, temperature);
  64. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  65. #else
  66. mavlink_raw_pressure_t packet;
  67. packet.time_usec = time_usec;
  68. packet.press_abs = press_abs;
  69. packet.press_diff1 = press_diff1;
  70. packet.press_diff2 = press_diff2;
  71. packet.temperature = temperature;
  72. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  73. #endif
  74. msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
  75. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  76. }
  77. /**
  78. * @brief Pack a raw_pressure message
  79. * @param system_id ID of this system
  80. * @param component_id ID of this component (e.g. 200 for IMU)
  81. * @param status MAVLink status structure
  82. * @param msg The MAVLink message to compress the data into
  83. *
  84. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  85. * @param press_abs Absolute pressure (raw)
  86. * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
  87. * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
  88. * @param temperature Raw Temperature measurement (raw)
  89. * @return length of the message in bytes (excluding serial stream start sign)
  90. */
  91. static inline uint16_t mavlink_msg_raw_pressure_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  92. uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
  93. {
  94. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  95. char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
  96. _mav_put_uint64_t(buf, 0, time_usec);
  97. _mav_put_int16_t(buf, 8, press_abs);
  98. _mav_put_int16_t(buf, 10, press_diff1);
  99. _mav_put_int16_t(buf, 12, press_diff2);
  100. _mav_put_int16_t(buf, 14, temperature);
  101. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  102. #else
  103. mavlink_raw_pressure_t packet;
  104. packet.time_usec = time_usec;
  105. packet.press_abs = press_abs;
  106. packet.press_diff1 = press_diff1;
  107. packet.press_diff2 = press_diff2;
  108. packet.temperature = temperature;
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  110. #endif
  111. msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
  112. #if MAVLINK_CRC_EXTRA
  113. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  114. #else
  115. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  116. #endif
  117. }
  118. /**
  119. * @brief Pack a raw_pressure message on a channel
  120. * @param system_id ID of this system
  121. * @param component_id ID of this component (e.g. 200 for IMU)
  122. * @param chan The MAVLink channel this message will be sent over
  123. * @param msg The MAVLink message to compress the data into
  124. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  125. * @param press_abs Absolute pressure (raw)
  126. * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
  127. * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
  128. * @param temperature Raw Temperature measurement (raw)
  129. * @return length of the message in bytes (excluding serial stream start sign)
  130. */
  131. static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  132. mavlink_message_t* msg,
  133. uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature)
  134. {
  135. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  136. char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
  137. _mav_put_uint64_t(buf, 0, time_usec);
  138. _mav_put_int16_t(buf, 8, press_abs);
  139. _mav_put_int16_t(buf, 10, press_diff1);
  140. _mav_put_int16_t(buf, 12, press_diff2);
  141. _mav_put_int16_t(buf, 14, temperature);
  142. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  143. #else
  144. mavlink_raw_pressure_t packet;
  145. packet.time_usec = time_usec;
  146. packet.press_abs = press_abs;
  147. packet.press_diff1 = press_diff1;
  148. packet.press_diff2 = press_diff2;
  149. packet.temperature = temperature;
  150. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  151. #endif
  152. msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
  153. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  154. }
  155. /**
  156. * @brief Encode a raw_pressure struct
  157. *
  158. * @param system_id ID of this system
  159. * @param component_id ID of this component (e.g. 200 for IMU)
  160. * @param msg The MAVLink message to compress the data into
  161. * @param raw_pressure C-struct to read the message contents from
  162. */
  163. 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)
  164. {
  165. 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);
  166. }
  167. /**
  168. * @brief Encode a raw_pressure struct on a channel
  169. *
  170. * @param system_id ID of this system
  171. * @param component_id ID of this component (e.g. 200 for IMU)
  172. * @param chan The MAVLink channel this message will be sent over
  173. * @param msg The MAVLink message to compress the data into
  174. * @param raw_pressure C-struct to read the message contents from
  175. */
  176. 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)
  177. {
  178. 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);
  179. }
  180. /**
  181. * @brief Encode a raw_pressure struct with provided status structure
  182. *
  183. * @param system_id ID of this system
  184. * @param component_id ID of this component (e.g. 200 for IMU)
  185. * @param status MAVLink status structure
  186. * @param msg The MAVLink message to compress the data into
  187. * @param raw_pressure C-struct to read the message contents from
  188. */
  189. static inline uint16_t mavlink_msg_raw_pressure_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
  190. {
  191. return mavlink_msg_raw_pressure_pack_status(system_id, component_id, _status, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
  192. }
  193. /**
  194. * @brief Send a raw_pressure message
  195. * @param chan MAVLink channel to send the message
  196. *
  197. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  198. * @param press_abs Absolute pressure (raw)
  199. * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent)
  200. * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent)
  201. * @param temperature Raw Temperature measurement (raw)
  202. */
  203. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  204. 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)
  205. {
  206. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  207. char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
  208. _mav_put_uint64_t(buf, 0, time_usec);
  209. _mav_put_int16_t(buf, 8, press_abs);
  210. _mav_put_int16_t(buf, 10, press_diff1);
  211. _mav_put_int16_t(buf, 12, press_diff2);
  212. _mav_put_int16_t(buf, 14, temperature);
  213. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  214. #else
  215. mavlink_raw_pressure_t packet;
  216. packet.time_usec = time_usec;
  217. packet.press_abs = press_abs;
  218. packet.press_diff1 = press_diff1;
  219. packet.press_diff2 = press_diff2;
  220. packet.temperature = temperature;
  221. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  222. #endif
  223. }
  224. /**
  225. * @brief Send a raw_pressure message
  226. * @param chan MAVLink channel to send the message
  227. * @param struct The MAVLink struct to serialize
  228. */
  229. static inline void mavlink_msg_raw_pressure_send_struct(mavlink_channel_t chan, const mavlink_raw_pressure_t* raw_pressure)
  230. {
  231. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  232. mavlink_msg_raw_pressure_send(chan, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
  233. #else
  234. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)raw_pressure, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  235. #endif
  236. }
  237. #if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  238. /*
  239. This variant of _send() can be used to save stack space by re-using
  240. memory from the receive buffer. The caller provides a
  241. mavlink_message_t which is the size of a full mavlink message. This
  242. is usually the receive buffer for the channel, and allows a reply to an
  243. incoming message with minimum stack space usage.
  244. */
  245. 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)
  246. {
  247. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  248. char *buf = (char *)msgbuf;
  249. _mav_put_uint64_t(buf, 0, time_usec);
  250. _mav_put_int16_t(buf, 8, press_abs);
  251. _mav_put_int16_t(buf, 10, press_diff1);
  252. _mav_put_int16_t(buf, 12, press_diff2);
  253. _mav_put_int16_t(buf, 14, temperature);
  254. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  255. #else
  256. mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf;
  257. packet->time_usec = time_usec;
  258. packet->press_abs = press_abs;
  259. packet->press_diff1 = press_diff1;
  260. packet->press_diff2 = press_diff2;
  261. packet->temperature = temperature;
  262. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
  263. #endif
  264. }
  265. #endif
  266. #endif
  267. // MESSAGE RAW_PRESSURE UNPACKING
  268. /**
  269. * @brief Get field time_usec from raw_pressure message
  270. *
  271. * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  272. */
  273. static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg)
  274. {
  275. return _MAV_RETURN_uint64_t(msg, 0);
  276. }
  277. /**
  278. * @brief Get field press_abs from raw_pressure message
  279. *
  280. * @return Absolute pressure (raw)
  281. */
  282. static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
  283. {
  284. return _MAV_RETURN_int16_t(msg, 8);
  285. }
  286. /**
  287. * @brief Get field press_diff1 from raw_pressure message
  288. *
  289. * @return Differential pressure 1 (raw, 0 if nonexistent)
  290. */
  291. static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
  292. {
  293. return _MAV_RETURN_int16_t(msg, 10);
  294. }
  295. /**
  296. * @brief Get field press_diff2 from raw_pressure message
  297. *
  298. * @return Differential pressure 2 (raw, 0 if nonexistent)
  299. */
  300. static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
  301. {
  302. return _MAV_RETURN_int16_t(msg, 12);
  303. }
  304. /**
  305. * @brief Get field temperature from raw_pressure message
  306. *
  307. * @return Raw Temperature measurement (raw)
  308. */
  309. static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
  310. {
  311. return _MAV_RETURN_int16_t(msg, 14);
  312. }
  313. /**
  314. * @brief Decode a raw_pressure message into a struct
  315. *
  316. * @param msg The message to decode
  317. * @param raw_pressure C-struct to decode the message contents into
  318. */
  319. static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
  320. {
  321. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  322. raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg);
  323. raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
  324. raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
  325. raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
  326. raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg);
  327. #else
  328. uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_RAW_PRESSURE_LEN;
  329. memset(raw_pressure, 0, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
  330. memcpy(raw_pressure, _MAV_PAYLOAD(msg), len);
  331. #endif
  332. }