mavlink_msg_named_value_float.h 13 KB

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