mavlink_msg_hil_state_quaternion.h 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580
  1. #pragma once
  2. // MESSAGE HIL_STATE_QUATERNION PACKING
  3. #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115
  4. typedef struct __mavlink_hil_state_quaternion_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. float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/
  7. float rollspeed; /*< [rad/s] Body frame roll / phi angular speed*/
  8. float pitchspeed; /*< [rad/s] Body frame pitch / theta angular speed*/
  9. float yawspeed; /*< [rad/s] Body frame yaw / psi angular speed*/
  10. int32_t lat; /*< [degE7] Latitude*/
  11. int32_t lon; /*< [degE7] Longitude*/
  12. int32_t alt; /*< [mm] Altitude*/
  13. int16_t vx; /*< [cm/s] Ground X Speed (Latitude)*/
  14. int16_t vy; /*< [cm/s] Ground Y Speed (Longitude)*/
  15. int16_t vz; /*< [cm/s] Ground Z Speed (Altitude)*/
  16. uint16_t ind_airspeed; /*< [cm/s] Indicated airspeed*/
  17. uint16_t true_airspeed; /*< [cm/s] True airspeed*/
  18. int16_t xacc; /*< [mG] X acceleration*/
  19. int16_t yacc; /*< [mG] Y acceleration*/
  20. int16_t zacc; /*< [mG] Z acceleration*/
  21. } mavlink_hil_state_quaternion_t;
  22. #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64
  23. #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN 64
  24. #define MAVLINK_MSG_ID_115_LEN 64
  25. #define MAVLINK_MSG_ID_115_MIN_LEN 64
  26. #define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4
  27. #define MAVLINK_MSG_ID_115_CRC 4
  28. #define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4
  29. #if MAVLINK_COMMAND_24BIT
  30. #define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \
  31. 115, \
  32. "HIL_STATE_QUATERNION", \
  33. 16, \
  34. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \
  35. { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \
  36. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \
  37. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \
  38. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \
  39. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \
  40. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \
  41. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \
  42. { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \
  43. { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \
  44. { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \
  45. { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \
  46. { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \
  47. { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \
  48. { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \
  49. { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \
  50. } \
  51. }
  52. #else
  53. #define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \
  54. "HIL_STATE_QUATERNION", \
  55. 16, \
  56. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \
  57. { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \
  58. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \
  59. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \
  60. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \
  61. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \
  62. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \
  63. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \
  64. { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \
  65. { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \
  66. { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \
  67. { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \
  68. { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \
  69. { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \
  70. { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \
  71. { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \
  72. } \
  73. }
  74. #endif
  75. /**
  76. * @brief Pack a hil_state_quaternion message
  77. * @param system_id ID of this system
  78. * @param component_id ID of this component (e.g. 200 for IMU)
  79. * @param msg The MAVLink message to compress the data into
  80. *
  81. * @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.
  82. * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
  83. * @param rollspeed [rad/s] Body frame roll / phi angular speed
  84. * @param pitchspeed [rad/s] Body frame pitch / theta angular speed
  85. * @param yawspeed [rad/s] Body frame yaw / psi angular speed
  86. * @param lat [degE7] Latitude
  87. * @param lon [degE7] Longitude
  88. * @param alt [mm] Altitude
  89. * @param vx [cm/s] Ground X Speed (Latitude)
  90. * @param vy [cm/s] Ground Y Speed (Longitude)
  91. * @param vz [cm/s] Ground Z Speed (Altitude)
  92. * @param ind_airspeed [cm/s] Indicated airspeed
  93. * @param true_airspeed [cm/s] True airspeed
  94. * @param xacc [mG] X acceleration
  95. * @param yacc [mG] Y acceleration
  96. * @param zacc [mG] Z acceleration
  97. * @return length of the message in bytes (excluding serial stream start sign)
  98. */
  99. static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  100. uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
  101. {
  102. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  103. char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
  104. _mav_put_uint64_t(buf, 0, time_usec);
  105. _mav_put_float(buf, 24, rollspeed);
  106. _mav_put_float(buf, 28, pitchspeed);
  107. _mav_put_float(buf, 32, yawspeed);
  108. _mav_put_int32_t(buf, 36, lat);
  109. _mav_put_int32_t(buf, 40, lon);
  110. _mav_put_int32_t(buf, 44, alt);
  111. _mav_put_int16_t(buf, 48, vx);
  112. _mav_put_int16_t(buf, 50, vy);
  113. _mav_put_int16_t(buf, 52, vz);
  114. _mav_put_uint16_t(buf, 54, ind_airspeed);
  115. _mav_put_uint16_t(buf, 56, true_airspeed);
  116. _mav_put_int16_t(buf, 58, xacc);
  117. _mav_put_int16_t(buf, 60, yacc);
  118. _mav_put_int16_t(buf, 62, zacc);
  119. _mav_put_float_array(buf, 8, attitude_quaternion, 4);
  120. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
  121. #else
  122. mavlink_hil_state_quaternion_t packet;
  123. packet.time_usec = time_usec;
  124. packet.rollspeed = rollspeed;
  125. packet.pitchspeed = pitchspeed;
  126. packet.yawspeed = yawspeed;
  127. packet.lat = lat;
  128. packet.lon = lon;
  129. packet.alt = alt;
  130. packet.vx = vx;
  131. packet.vy = vy;
  132. packet.vz = vz;
  133. packet.ind_airspeed = ind_airspeed;
  134. packet.true_airspeed = true_airspeed;
  135. packet.xacc = xacc;
  136. packet.yacc = yacc;
  137. packet.zacc = zacc;
  138. mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
  139. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
  140. #endif
  141. msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
  142. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
  143. }
  144. /**
  145. * @brief Pack a hil_state_quaternion message on a channel
  146. * @param system_id ID of this system
  147. * @param component_id ID of this component (e.g. 200 for IMU)
  148. * @param chan The MAVLink channel this message will be sent over
  149. * @param msg The MAVLink message to compress the data into
  150. * @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.
  151. * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
  152. * @param rollspeed [rad/s] Body frame roll / phi angular speed
  153. * @param pitchspeed [rad/s] Body frame pitch / theta angular speed
  154. * @param yawspeed [rad/s] Body frame yaw / psi angular speed
  155. * @param lat [degE7] Latitude
  156. * @param lon [degE7] Longitude
  157. * @param alt [mm] Altitude
  158. * @param vx [cm/s] Ground X Speed (Latitude)
  159. * @param vy [cm/s] Ground Y Speed (Longitude)
  160. * @param vz [cm/s] Ground Z Speed (Altitude)
  161. * @param ind_airspeed [cm/s] Indicated airspeed
  162. * @param true_airspeed [cm/s] True airspeed
  163. * @param xacc [mG] X acceleration
  164. * @param yacc [mG] Y acceleration
  165. * @param zacc [mG] Z acceleration
  166. * @return length of the message in bytes (excluding serial stream start sign)
  167. */
  168. static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  169. mavlink_message_t* msg,
  170. uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc)
  171. {
  172. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  173. char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
  174. _mav_put_uint64_t(buf, 0, time_usec);
  175. _mav_put_float(buf, 24, rollspeed);
  176. _mav_put_float(buf, 28, pitchspeed);
  177. _mav_put_float(buf, 32, yawspeed);
  178. _mav_put_int32_t(buf, 36, lat);
  179. _mav_put_int32_t(buf, 40, lon);
  180. _mav_put_int32_t(buf, 44, alt);
  181. _mav_put_int16_t(buf, 48, vx);
  182. _mav_put_int16_t(buf, 50, vy);
  183. _mav_put_int16_t(buf, 52, vz);
  184. _mav_put_uint16_t(buf, 54, ind_airspeed);
  185. _mav_put_uint16_t(buf, 56, true_airspeed);
  186. _mav_put_int16_t(buf, 58, xacc);
  187. _mav_put_int16_t(buf, 60, yacc);
  188. _mav_put_int16_t(buf, 62, zacc);
  189. _mav_put_float_array(buf, 8, attitude_quaternion, 4);
  190. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
  191. #else
  192. mavlink_hil_state_quaternion_t packet;
  193. packet.time_usec = time_usec;
  194. packet.rollspeed = rollspeed;
  195. packet.pitchspeed = pitchspeed;
  196. packet.yawspeed = yawspeed;
  197. packet.lat = lat;
  198. packet.lon = lon;
  199. packet.alt = alt;
  200. packet.vx = vx;
  201. packet.vy = vy;
  202. packet.vz = vz;
  203. packet.ind_airspeed = ind_airspeed;
  204. packet.true_airspeed = true_airspeed;
  205. packet.xacc = xacc;
  206. packet.yacc = yacc;
  207. packet.zacc = zacc;
  208. mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
  209. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
  210. #endif
  211. msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
  212. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
  213. }
  214. /**
  215. * @brief Encode a hil_state_quaternion struct
  216. *
  217. * @param system_id ID of this system
  218. * @param component_id ID of this component (e.g. 200 for IMU)
  219. * @param msg The MAVLink message to compress the data into
  220. * @param hil_state_quaternion C-struct to read the message contents from
  221. */
  222. static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
  223. {
  224. return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
  225. }
  226. /**
  227. * @brief Encode a hil_state_quaternion struct on a channel
  228. *
  229. * @param system_id ID of this system
  230. * @param component_id ID of this component (e.g. 200 for IMU)
  231. * @param chan The MAVLink channel this message will be sent over
  232. * @param msg The MAVLink message to compress the data into
  233. * @param hil_state_quaternion C-struct to read the message contents from
  234. */
  235. static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
  236. {
  237. return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
  238. }
  239. /**
  240. * @brief Send a hil_state_quaternion message
  241. * @param chan MAVLink channel to send the message
  242. *
  243. * @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.
  244. * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
  245. * @param rollspeed [rad/s] Body frame roll / phi angular speed
  246. * @param pitchspeed [rad/s] Body frame pitch / theta angular speed
  247. * @param yawspeed [rad/s] Body frame yaw / psi angular speed
  248. * @param lat [degE7] Latitude
  249. * @param lon [degE7] Longitude
  250. * @param alt [mm] Altitude
  251. * @param vx [cm/s] Ground X Speed (Latitude)
  252. * @param vy [cm/s] Ground Y Speed (Longitude)
  253. * @param vz [cm/s] Ground Z Speed (Altitude)
  254. * @param ind_airspeed [cm/s] Indicated airspeed
  255. * @param true_airspeed [cm/s] True airspeed
  256. * @param xacc [mG] X acceleration
  257. * @param yacc [mG] Y acceleration
  258. * @param zacc [mG] Z acceleration
  259. */
  260. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  261. static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
  262. {
  263. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  264. char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
  265. _mav_put_uint64_t(buf, 0, time_usec);
  266. _mav_put_float(buf, 24, rollspeed);
  267. _mav_put_float(buf, 28, pitchspeed);
  268. _mav_put_float(buf, 32, yawspeed);
  269. _mav_put_int32_t(buf, 36, lat);
  270. _mav_put_int32_t(buf, 40, lon);
  271. _mav_put_int32_t(buf, 44, alt);
  272. _mav_put_int16_t(buf, 48, vx);
  273. _mav_put_int16_t(buf, 50, vy);
  274. _mav_put_int16_t(buf, 52, vz);
  275. _mav_put_uint16_t(buf, 54, ind_airspeed);
  276. _mav_put_uint16_t(buf, 56, true_airspeed);
  277. _mav_put_int16_t(buf, 58, xacc);
  278. _mav_put_int16_t(buf, 60, yacc);
  279. _mav_put_int16_t(buf, 62, zacc);
  280. _mav_put_float_array(buf, 8, attitude_quaternion, 4);
  281. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
  282. #else
  283. mavlink_hil_state_quaternion_t packet;
  284. packet.time_usec = time_usec;
  285. packet.rollspeed = rollspeed;
  286. packet.pitchspeed = pitchspeed;
  287. packet.yawspeed = yawspeed;
  288. packet.lat = lat;
  289. packet.lon = lon;
  290. packet.alt = alt;
  291. packet.vx = vx;
  292. packet.vy = vy;
  293. packet.vz = vz;
  294. packet.ind_airspeed = ind_airspeed;
  295. packet.true_airspeed = true_airspeed;
  296. packet.xacc = xacc;
  297. packet.yacc = yacc;
  298. packet.zacc = zacc;
  299. mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
  300. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
  301. #endif
  302. }
  303. /**
  304. * @brief Send a hil_state_quaternion message
  305. * @param chan MAVLink channel to send the message
  306. * @param struct The MAVLink struct to serialize
  307. */
  308. static inline void mavlink_msg_hil_state_quaternion_send_struct(mavlink_channel_t chan, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
  309. {
  310. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  311. mavlink_msg_hil_state_quaternion_send(chan, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
  312. #else
  313. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)hil_state_quaternion, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
  314. #endif
  315. }
  316. #if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  317. /*
  318. This variant of _send() can be used to save stack space by re-using
  319. memory from the receive buffer. The caller provides a
  320. mavlink_message_t which is the size of a full mavlink message. This
  321. is usually the receive buffer for the channel, and allows a reply to an
  322. incoming message with minimum stack space usage.
  323. */
  324. static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
  325. {
  326. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  327. char *buf = (char *)msgbuf;
  328. _mav_put_uint64_t(buf, 0, time_usec);
  329. _mav_put_float(buf, 24, rollspeed);
  330. _mav_put_float(buf, 28, pitchspeed);
  331. _mav_put_float(buf, 32, yawspeed);
  332. _mav_put_int32_t(buf, 36, lat);
  333. _mav_put_int32_t(buf, 40, lon);
  334. _mav_put_int32_t(buf, 44, alt);
  335. _mav_put_int16_t(buf, 48, vx);
  336. _mav_put_int16_t(buf, 50, vy);
  337. _mav_put_int16_t(buf, 52, vz);
  338. _mav_put_uint16_t(buf, 54, ind_airspeed);
  339. _mav_put_uint16_t(buf, 56, true_airspeed);
  340. _mav_put_int16_t(buf, 58, xacc);
  341. _mav_put_int16_t(buf, 60, yacc);
  342. _mav_put_int16_t(buf, 62, zacc);
  343. _mav_put_float_array(buf, 8, attitude_quaternion, 4);
  344. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
  345. #else
  346. mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf;
  347. packet->time_usec = time_usec;
  348. packet->rollspeed = rollspeed;
  349. packet->pitchspeed = pitchspeed;
  350. packet->yawspeed = yawspeed;
  351. packet->lat = lat;
  352. packet->lon = lon;
  353. packet->alt = alt;
  354. packet->vx = vx;
  355. packet->vy = vy;
  356. packet->vz = vz;
  357. packet->ind_airspeed = ind_airspeed;
  358. packet->true_airspeed = true_airspeed;
  359. packet->xacc = xacc;
  360. packet->yacc = yacc;
  361. packet->zacc = zacc;
  362. mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4);
  363. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
  364. #endif
  365. }
  366. #endif
  367. #endif
  368. // MESSAGE HIL_STATE_QUATERNION UNPACKING
  369. /**
  370. * @brief Get field time_usec from hil_state_quaternion message
  371. *
  372. * @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.
  373. */
  374. static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg)
  375. {
  376. return _MAV_RETURN_uint64_t(msg, 0);
  377. }
  378. /**
  379. * @brief Get field attitude_quaternion from hil_state_quaternion message
  380. *
  381. * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
  382. */
  383. static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion)
  384. {
  385. return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8);
  386. }
  387. /**
  388. * @brief Get field rollspeed from hil_state_quaternion message
  389. *
  390. * @return [rad/s] Body frame roll / phi angular speed
  391. */
  392. static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg)
  393. {
  394. return _MAV_RETURN_float(msg, 24);
  395. }
  396. /**
  397. * @brief Get field pitchspeed from hil_state_quaternion message
  398. *
  399. * @return [rad/s] Body frame pitch / theta angular speed
  400. */
  401. static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg)
  402. {
  403. return _MAV_RETURN_float(msg, 28);
  404. }
  405. /**
  406. * @brief Get field yawspeed from hil_state_quaternion message
  407. *
  408. * @return [rad/s] Body frame yaw / psi angular speed
  409. */
  410. static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg)
  411. {
  412. return _MAV_RETURN_float(msg, 32);
  413. }
  414. /**
  415. * @brief Get field lat from hil_state_quaternion message
  416. *
  417. * @return [degE7] Latitude
  418. */
  419. static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg)
  420. {
  421. return _MAV_RETURN_int32_t(msg, 36);
  422. }
  423. /**
  424. * @brief Get field lon from hil_state_quaternion message
  425. *
  426. * @return [degE7] Longitude
  427. */
  428. static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg)
  429. {
  430. return _MAV_RETURN_int32_t(msg, 40);
  431. }
  432. /**
  433. * @brief Get field alt from hil_state_quaternion message
  434. *
  435. * @return [mm] Altitude
  436. */
  437. static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg)
  438. {
  439. return _MAV_RETURN_int32_t(msg, 44);
  440. }
  441. /**
  442. * @brief Get field vx from hil_state_quaternion message
  443. *
  444. * @return [cm/s] Ground X Speed (Latitude)
  445. */
  446. static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg)
  447. {
  448. return _MAV_RETURN_int16_t(msg, 48);
  449. }
  450. /**
  451. * @brief Get field vy from hil_state_quaternion message
  452. *
  453. * @return [cm/s] Ground Y Speed (Longitude)
  454. */
  455. static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg)
  456. {
  457. return _MAV_RETURN_int16_t(msg, 50);
  458. }
  459. /**
  460. * @brief Get field vz from hil_state_quaternion message
  461. *
  462. * @return [cm/s] Ground Z Speed (Altitude)
  463. */
  464. static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg)
  465. {
  466. return _MAV_RETURN_int16_t(msg, 52);
  467. }
  468. /**
  469. * @brief Get field ind_airspeed from hil_state_quaternion message
  470. *
  471. * @return [cm/s] Indicated airspeed
  472. */
  473. static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg)
  474. {
  475. return _MAV_RETURN_uint16_t(msg, 54);
  476. }
  477. /**
  478. * @brief Get field true_airspeed from hil_state_quaternion message
  479. *
  480. * @return [cm/s] True airspeed
  481. */
  482. static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg)
  483. {
  484. return _MAV_RETURN_uint16_t(msg, 56);
  485. }
  486. /**
  487. * @brief Get field xacc from hil_state_quaternion message
  488. *
  489. * @return [mG] X acceleration
  490. */
  491. static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg)
  492. {
  493. return _MAV_RETURN_int16_t(msg, 58);
  494. }
  495. /**
  496. * @brief Get field yacc from hil_state_quaternion message
  497. *
  498. * @return [mG] Y acceleration
  499. */
  500. static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg)
  501. {
  502. return _MAV_RETURN_int16_t(msg, 60);
  503. }
  504. /**
  505. * @brief Get field zacc from hil_state_quaternion message
  506. *
  507. * @return [mG] Z acceleration
  508. */
  509. static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg)
  510. {
  511. return _MAV_RETURN_int16_t(msg, 62);
  512. }
  513. /**
  514. * @brief Decode a hil_state_quaternion message into a struct
  515. *
  516. * @param msg The message to decode
  517. * @param hil_state_quaternion C-struct to decode the message contents into
  518. */
  519. static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion)
  520. {
  521. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  522. hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg);
  523. mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion);
  524. hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg);
  525. hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg);
  526. hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg);
  527. hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg);
  528. hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg);
  529. hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg);
  530. hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg);
  531. hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg);
  532. hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg);
  533. hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg);
  534. hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg);
  535. hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg);
  536. hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg);
  537. hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg);
  538. #else
  539. uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN;
  540. memset(hil_state_quaternion, 0, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
  541. memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), len);
  542. #endif
  543. }