mavlink_msg_scaled_pressure.h 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313
  1. #pragma once
  2. // MESSAGE SCALED_PRESSURE PACKING
  3. #define MAVLINK_MSG_ID_SCALED_PRESSURE 29
  4. typedef struct __mavlink_scaled_pressure_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  6. float press_abs; /*< [hPa] Absolute pressure*/
  7. float press_diff; /*< [hPa] Differential pressure 1*/
  8. int16_t temperature; /*< [cdegC] Absolute pressure temperature*/
  9. int16_t temperature_press_diff; /*< [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.*/
  10. } mavlink_scaled_pressure_t;
  11. #define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 16
  12. #define MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN 14
  13. #define MAVLINK_MSG_ID_29_LEN 16
  14. #define MAVLINK_MSG_ID_29_MIN_LEN 14
  15. #define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115
  16. #define MAVLINK_MSG_ID_29_CRC 115
  17. #if MAVLINK_COMMAND_24BIT
  18. #define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \
  19. 29, \
  20. "SCALED_PRESSURE", \
  21. 5, \
  22. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \
  23. { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \
  24. { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \
  25. { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \
  26. { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure_t, temperature_press_diff) }, \
  27. } \
  28. }
  29. #else
  30. #define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \
  31. "SCALED_PRESSURE", \
  32. 5, \
  33. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \
  34. { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \
  35. { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \
  36. { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \
  37. { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure_t, temperature_press_diff) }, \
  38. } \
  39. }
  40. #endif
  41. /**
  42. * @brief Pack a scaled_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_boot_ms [ms] Timestamp (time since system boot).
  48. * @param press_abs [hPa] Absolute pressure
  49. * @param press_diff [hPa] Differential pressure 1
  50. * @param temperature [cdegC] Absolute pressure temperature
  51. * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
  52. * @return length of the message in bytes (excluding serial stream start sign)
  53. */
  54. static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  55. uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff)
  56. {
  57. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  58. char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
  59. _mav_put_uint32_t(buf, 0, time_boot_ms);
  60. _mav_put_float(buf, 4, press_abs);
  61. _mav_put_float(buf, 8, press_diff);
  62. _mav_put_int16_t(buf, 12, temperature);
  63. _mav_put_int16_t(buf, 14, temperature_press_diff);
  64. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
  65. #else
  66. mavlink_scaled_pressure_t packet;
  67. packet.time_boot_ms = time_boot_ms;
  68. packet.press_abs = press_abs;
  69. packet.press_diff = press_diff;
  70. packet.temperature = temperature;
  71. packet.temperature_press_diff = temperature_press_diff;
  72. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
  73. #endif
  74. msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
  75. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
  76. }
  77. /**
  78. * @brief Pack a scaled_pressure message on a channel
  79. * @param system_id ID of this system
  80. * @param component_id ID of this component (e.g. 200 for IMU)
  81. * @param chan The MAVLink channel this message will be sent over
  82. * @param msg The MAVLink message to compress the data into
  83. * @param time_boot_ms [ms] Timestamp (time since system boot).
  84. * @param press_abs [hPa] Absolute pressure
  85. * @param press_diff [hPa] Differential pressure 1
  86. * @param temperature [cdegC] Absolute pressure temperature
  87. * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
  88. * @return length of the message in bytes (excluding serial stream start sign)
  89. */
  90. static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  91. mavlink_message_t* msg,
  92. uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature,int16_t temperature_press_diff)
  93. {
  94. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  95. char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
  96. _mav_put_uint32_t(buf, 0, time_boot_ms);
  97. _mav_put_float(buf, 4, press_abs);
  98. _mav_put_float(buf, 8, press_diff);
  99. _mav_put_int16_t(buf, 12, temperature);
  100. _mav_put_int16_t(buf, 14, temperature_press_diff);
  101. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
  102. #else
  103. mavlink_scaled_pressure_t packet;
  104. packet.time_boot_ms = time_boot_ms;
  105. packet.press_abs = press_abs;
  106. packet.press_diff = press_diff;
  107. packet.temperature = temperature;
  108. packet.temperature_press_diff = temperature_press_diff;
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
  110. #endif
  111. msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
  112. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
  113. }
  114. /**
  115. * @brief Encode a scaled_pressure struct
  116. *
  117. * @param system_id ID of this system
  118. * @param component_id ID of this component (e.g. 200 for IMU)
  119. * @param msg The MAVLink message to compress the data into
  120. * @param scaled_pressure C-struct to read the message contents from
  121. */
  122. static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
  123. {
  124. return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature, scaled_pressure->temperature_press_diff);
  125. }
  126. /**
  127. * @brief Encode a scaled_pressure struct on a channel
  128. *
  129. * @param system_id ID of this system
  130. * @param component_id ID of this component (e.g. 200 for IMU)
  131. * @param chan The MAVLink channel this message will be sent over
  132. * @param msg The MAVLink message to compress the data into
  133. * @param scaled_pressure C-struct to read the message contents from
  134. */
  135. static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
  136. {
  137. return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature, scaled_pressure->temperature_press_diff);
  138. }
  139. /**
  140. * @brief Send a scaled_pressure message
  141. * @param chan MAVLink channel to send the message
  142. *
  143. * @param time_boot_ms [ms] Timestamp (time since system boot).
  144. * @param press_abs [hPa] Absolute pressure
  145. * @param press_diff [hPa] Differential pressure 1
  146. * @param temperature [cdegC] Absolute pressure temperature
  147. * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
  148. */
  149. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  150. static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff)
  151. {
  152. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  153. char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
  154. _mav_put_uint32_t(buf, 0, time_boot_ms);
  155. _mav_put_float(buf, 4, press_abs);
  156. _mav_put_float(buf, 8, press_diff);
  157. _mav_put_int16_t(buf, 12, temperature);
  158. _mav_put_int16_t(buf, 14, temperature_press_diff);
  159. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
  160. #else
  161. mavlink_scaled_pressure_t packet;
  162. packet.time_boot_ms = time_boot_ms;
  163. packet.press_abs = press_abs;
  164. packet.press_diff = press_diff;
  165. packet.temperature = temperature;
  166. packet.temperature_press_diff = temperature_press_diff;
  167. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
  168. #endif
  169. }
  170. /**
  171. * @brief Send a scaled_pressure message
  172. * @param chan MAVLink channel to send the message
  173. * @param struct The MAVLink struct to serialize
  174. */
  175. static inline void mavlink_msg_scaled_pressure_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure_t* scaled_pressure)
  176. {
  177. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  178. mavlink_msg_scaled_pressure_send(chan, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature, scaled_pressure->temperature_press_diff);
  179. #else
  180. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)scaled_pressure, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
  181. #endif
  182. }
  183. #if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  184. /*
  185. This variant of _send() can be used to save stack space by re-using
  186. memory from the receive buffer. The caller provides a
  187. mavlink_message_t which is the size of a full mavlink message. This
  188. is usually the receive buffer for the channel, and allows a reply to an
  189. incoming message with minimum stack space usage.
  190. */
  191. static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff)
  192. {
  193. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  194. char *buf = (char *)msgbuf;
  195. _mav_put_uint32_t(buf, 0, time_boot_ms);
  196. _mav_put_float(buf, 4, press_abs);
  197. _mav_put_float(buf, 8, press_diff);
  198. _mav_put_int16_t(buf, 12, temperature);
  199. _mav_put_int16_t(buf, 14, temperature_press_diff);
  200. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
  201. #else
  202. mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf;
  203. packet->time_boot_ms = time_boot_ms;
  204. packet->press_abs = press_abs;
  205. packet->press_diff = press_diff;
  206. packet->temperature = temperature;
  207. packet->temperature_press_diff = temperature_press_diff;
  208. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
  209. #endif
  210. }
  211. #endif
  212. #endif
  213. // MESSAGE SCALED_PRESSURE UNPACKING
  214. /**
  215. * @brief Get field time_boot_ms from scaled_pressure message
  216. *
  217. * @return [ms] Timestamp (time since system boot).
  218. */
  219. static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg)
  220. {
  221. return _MAV_RETURN_uint32_t(msg, 0);
  222. }
  223. /**
  224. * @brief Get field press_abs from scaled_pressure message
  225. *
  226. * @return [hPa] Absolute pressure
  227. */
  228. static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg)
  229. {
  230. return _MAV_RETURN_float(msg, 4);
  231. }
  232. /**
  233. * @brief Get field press_diff from scaled_pressure message
  234. *
  235. * @return [hPa] Differential pressure 1
  236. */
  237. static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg)
  238. {
  239. return _MAV_RETURN_float(msg, 8);
  240. }
  241. /**
  242. * @brief Get field temperature from scaled_pressure message
  243. *
  244. * @return [cdegC] Absolute pressure temperature
  245. */
  246. static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg)
  247. {
  248. return _MAV_RETURN_int16_t(msg, 12);
  249. }
  250. /**
  251. * @brief Get field temperature_press_diff from scaled_pressure message
  252. *
  253. * @return [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
  254. */
  255. static inline int16_t mavlink_msg_scaled_pressure_get_temperature_press_diff(const mavlink_message_t* msg)
  256. {
  257. return _MAV_RETURN_int16_t(msg, 14);
  258. }
  259. /**
  260. * @brief Decode a scaled_pressure message into a struct
  261. *
  262. * @param msg The message to decode
  263. * @param scaled_pressure C-struct to decode the message contents into
  264. */
  265. static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure)
  266. {
  267. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  268. scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg);
  269. scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg);
  270. scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg);
  271. scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg);
  272. scaled_pressure->temperature_press_diff = mavlink_msg_scaled_pressure_get_temperature_press_diff(msg);
  273. #else
  274. uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE_LEN;
  275. memset(scaled_pressure, 0, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
  276. memcpy(scaled_pressure, _MAV_PAYLOAD(msg), len);
  277. #endif
  278. }