mavlink_msg_control_system_state.h 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607
  1. #pragma once
  2. // MESSAGE CONTROL_SYSTEM_STATE PACKING
  3. #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146
  4. typedef struct __mavlink_control_system_state_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 x_acc; /*< [m/s/s] X acceleration in body frame*/
  7. float y_acc; /*< [m/s/s] Y acceleration in body frame*/
  8. float z_acc; /*< [m/s/s] Z acceleration in body frame*/
  9. float x_vel; /*< [m/s] X velocity in body frame*/
  10. float y_vel; /*< [m/s] Y velocity in body frame*/
  11. float z_vel; /*< [m/s] Z velocity in body frame*/
  12. float x_pos; /*< [m] X position in local frame*/
  13. float y_pos; /*< [m] Y position in local frame*/
  14. float z_pos; /*< [m] Z position in local frame*/
  15. float airspeed; /*< [m/s] Airspeed, set to -1 if unknown*/
  16. float vel_variance[3]; /*< Variance of body velocity estimate*/
  17. float pos_variance[3]; /*< Variance in local position*/
  18. float q[4]; /*< The attitude, represented as Quaternion*/
  19. float roll_rate; /*< [rad/s] Angular rate in roll axis*/
  20. float pitch_rate; /*< [rad/s] Angular rate in pitch axis*/
  21. float yaw_rate; /*< [rad/s] Angular rate in yaw axis*/
  22. } mavlink_control_system_state_t;
  23. #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100
  24. #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN 100
  25. #define MAVLINK_MSG_ID_146_LEN 100
  26. #define MAVLINK_MSG_ID_146_MIN_LEN 100
  27. #define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103
  28. #define MAVLINK_MSG_ID_146_CRC 103
  29. #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3
  30. #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3
  31. #define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4
  32. #if MAVLINK_COMMAND_24BIT
  33. #define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \
  34. 146, \
  35. "CONTROL_SYSTEM_STATE", \
  36. 17, \
  37. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \
  38. { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \
  39. { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \
  40. { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \
  41. { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \
  42. { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \
  43. { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \
  44. { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \
  45. { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \
  46. { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \
  47. { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \
  48. { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \
  49. { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \
  50. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \
  51. { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \
  52. { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \
  53. { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \
  54. } \
  55. }
  56. #else
  57. #define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \
  58. "CONTROL_SYSTEM_STATE", \
  59. 17, \
  60. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \
  61. { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \
  62. { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \
  63. { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \
  64. { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \
  65. { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \
  66. { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \
  67. { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \
  68. { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \
  69. { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \
  70. { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \
  71. { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \
  72. { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \
  73. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \
  74. { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \
  75. { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \
  76. { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \
  77. } \
  78. }
  79. #endif
  80. /**
  81. * @brief Pack a control_system_state message
  82. * @param system_id ID of this system
  83. * @param component_id ID of this component (e.g. 200 for IMU)
  84. * @param msg The MAVLink message to compress the data into
  85. *
  86. * @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.
  87. * @param x_acc [m/s/s] X acceleration in body frame
  88. * @param y_acc [m/s/s] Y acceleration in body frame
  89. * @param z_acc [m/s/s] Z acceleration in body frame
  90. * @param x_vel [m/s] X velocity in body frame
  91. * @param y_vel [m/s] Y velocity in body frame
  92. * @param z_vel [m/s] Z velocity in body frame
  93. * @param x_pos [m] X position in local frame
  94. * @param y_pos [m] Y position in local frame
  95. * @param z_pos [m] Z position in local frame
  96. * @param airspeed [m/s] Airspeed, set to -1 if unknown
  97. * @param vel_variance Variance of body velocity estimate
  98. * @param pos_variance Variance in local position
  99. * @param q The attitude, represented as Quaternion
  100. * @param roll_rate [rad/s] Angular rate in roll axis
  101. * @param pitch_rate [rad/s] Angular rate in pitch axis
  102. * @param yaw_rate [rad/s] Angular rate in yaw axis
  103. * @return length of the message in bytes (excluding serial stream start sign)
  104. */
  105. static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  106. uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate)
  107. {
  108. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  109. char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN];
  110. _mav_put_uint64_t(buf, 0, time_usec);
  111. _mav_put_float(buf, 8, x_acc);
  112. _mav_put_float(buf, 12, y_acc);
  113. _mav_put_float(buf, 16, z_acc);
  114. _mav_put_float(buf, 20, x_vel);
  115. _mav_put_float(buf, 24, y_vel);
  116. _mav_put_float(buf, 28, z_vel);
  117. _mav_put_float(buf, 32, x_pos);
  118. _mav_put_float(buf, 36, y_pos);
  119. _mav_put_float(buf, 40, z_pos);
  120. _mav_put_float(buf, 44, airspeed);
  121. _mav_put_float(buf, 88, roll_rate);
  122. _mav_put_float(buf, 92, pitch_rate);
  123. _mav_put_float(buf, 96, yaw_rate);
  124. _mav_put_float_array(buf, 48, vel_variance, 3);
  125. _mav_put_float_array(buf, 60, pos_variance, 3);
  126. _mav_put_float_array(buf, 72, q, 4);
  127. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
  128. #else
  129. mavlink_control_system_state_t packet;
  130. packet.time_usec = time_usec;
  131. packet.x_acc = x_acc;
  132. packet.y_acc = y_acc;
  133. packet.z_acc = z_acc;
  134. packet.x_vel = x_vel;
  135. packet.y_vel = y_vel;
  136. packet.z_vel = z_vel;
  137. packet.x_pos = x_pos;
  138. packet.y_pos = y_pos;
  139. packet.z_pos = z_pos;
  140. packet.airspeed = airspeed;
  141. packet.roll_rate = roll_rate;
  142. packet.pitch_rate = pitch_rate;
  143. packet.yaw_rate = yaw_rate;
  144. mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3);
  145. mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3);
  146. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  147. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
  148. #endif
  149. msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE;
  150. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
  151. }
  152. /**
  153. * @brief Pack a control_system_state message on a channel
  154. * @param system_id ID of this system
  155. * @param component_id ID of this component (e.g. 200 for IMU)
  156. * @param chan The MAVLink channel this message will be sent over
  157. * @param msg The MAVLink message to compress the data into
  158. * @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.
  159. * @param x_acc [m/s/s] X acceleration in body frame
  160. * @param y_acc [m/s/s] Y acceleration in body frame
  161. * @param z_acc [m/s/s] Z acceleration in body frame
  162. * @param x_vel [m/s] X velocity in body frame
  163. * @param y_vel [m/s] Y velocity in body frame
  164. * @param z_vel [m/s] Z velocity in body frame
  165. * @param x_pos [m] X position in local frame
  166. * @param y_pos [m] Y position in local frame
  167. * @param z_pos [m] Z position in local frame
  168. * @param airspeed [m/s] Airspeed, set to -1 if unknown
  169. * @param vel_variance Variance of body velocity estimate
  170. * @param pos_variance Variance in local position
  171. * @param q The attitude, represented as Quaternion
  172. * @param roll_rate [rad/s] Angular rate in roll axis
  173. * @param pitch_rate [rad/s] Angular rate in pitch axis
  174. * @param yaw_rate [rad/s] Angular rate in yaw axis
  175. * @return length of the message in bytes (excluding serial stream start sign)
  176. */
  177. static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  178. mavlink_message_t* msg,
  179. uint64_t time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,const float *vel_variance,const float *pos_variance,const float *q,float roll_rate,float pitch_rate,float yaw_rate)
  180. {
  181. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  182. char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN];
  183. _mav_put_uint64_t(buf, 0, time_usec);
  184. _mav_put_float(buf, 8, x_acc);
  185. _mav_put_float(buf, 12, y_acc);
  186. _mav_put_float(buf, 16, z_acc);
  187. _mav_put_float(buf, 20, x_vel);
  188. _mav_put_float(buf, 24, y_vel);
  189. _mav_put_float(buf, 28, z_vel);
  190. _mav_put_float(buf, 32, x_pos);
  191. _mav_put_float(buf, 36, y_pos);
  192. _mav_put_float(buf, 40, z_pos);
  193. _mav_put_float(buf, 44, airspeed);
  194. _mav_put_float(buf, 88, roll_rate);
  195. _mav_put_float(buf, 92, pitch_rate);
  196. _mav_put_float(buf, 96, yaw_rate);
  197. _mav_put_float_array(buf, 48, vel_variance, 3);
  198. _mav_put_float_array(buf, 60, pos_variance, 3);
  199. _mav_put_float_array(buf, 72, q, 4);
  200. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
  201. #else
  202. mavlink_control_system_state_t packet;
  203. packet.time_usec = time_usec;
  204. packet.x_acc = x_acc;
  205. packet.y_acc = y_acc;
  206. packet.z_acc = z_acc;
  207. packet.x_vel = x_vel;
  208. packet.y_vel = y_vel;
  209. packet.z_vel = z_vel;
  210. packet.x_pos = x_pos;
  211. packet.y_pos = y_pos;
  212. packet.z_pos = z_pos;
  213. packet.airspeed = airspeed;
  214. packet.roll_rate = roll_rate;
  215. packet.pitch_rate = pitch_rate;
  216. packet.yaw_rate = yaw_rate;
  217. mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3);
  218. mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3);
  219. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  220. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
  221. #endif
  222. msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE;
  223. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
  224. }
  225. /**
  226. * @brief Encode a control_system_state struct
  227. *
  228. * @param system_id ID of this system
  229. * @param component_id ID of this component (e.g. 200 for IMU)
  230. * @param msg The MAVLink message to compress the data into
  231. * @param control_system_state C-struct to read the message contents from
  232. */
  233. static inline uint16_t mavlink_msg_control_system_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state)
  234. {
  235. return mavlink_msg_control_system_state_pack(system_id, component_id, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate);
  236. }
  237. /**
  238. * @brief Encode a control_system_state struct on a channel
  239. *
  240. * @param system_id ID of this system
  241. * @param component_id ID of this component (e.g. 200 for IMU)
  242. * @param chan The MAVLink channel this message will be sent over
  243. * @param msg The MAVLink message to compress the data into
  244. * @param control_system_state C-struct to read the message contents from
  245. */
  246. static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state)
  247. {
  248. return mavlink_msg_control_system_state_pack_chan(system_id, component_id, chan, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate);
  249. }
  250. /**
  251. * @brief Send a control_system_state message
  252. * @param chan MAVLink channel to send the message
  253. *
  254. * @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.
  255. * @param x_acc [m/s/s] X acceleration in body frame
  256. * @param y_acc [m/s/s] Y acceleration in body frame
  257. * @param z_acc [m/s/s] Z acceleration in body frame
  258. * @param x_vel [m/s] X velocity in body frame
  259. * @param y_vel [m/s] Y velocity in body frame
  260. * @param z_vel [m/s] Z velocity in body frame
  261. * @param x_pos [m] X position in local frame
  262. * @param y_pos [m] Y position in local frame
  263. * @param z_pos [m] Z position in local frame
  264. * @param airspeed [m/s] Airspeed, set to -1 if unknown
  265. * @param vel_variance Variance of body velocity estimate
  266. * @param pos_variance Variance in local position
  267. * @param q The attitude, represented as Quaternion
  268. * @param roll_rate [rad/s] Angular rate in roll axis
  269. * @param pitch_rate [rad/s] Angular rate in pitch axis
  270. * @param yaw_rate [rad/s] Angular rate in yaw axis
  271. */
  272. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  273. static inline void mavlink_msg_control_system_state_send(mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate)
  274. {
  275. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  276. char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN];
  277. _mav_put_uint64_t(buf, 0, time_usec);
  278. _mav_put_float(buf, 8, x_acc);
  279. _mav_put_float(buf, 12, y_acc);
  280. _mav_put_float(buf, 16, z_acc);
  281. _mav_put_float(buf, 20, x_vel);
  282. _mav_put_float(buf, 24, y_vel);
  283. _mav_put_float(buf, 28, z_vel);
  284. _mav_put_float(buf, 32, x_pos);
  285. _mav_put_float(buf, 36, y_pos);
  286. _mav_put_float(buf, 40, z_pos);
  287. _mav_put_float(buf, 44, airspeed);
  288. _mav_put_float(buf, 88, roll_rate);
  289. _mav_put_float(buf, 92, pitch_rate);
  290. _mav_put_float(buf, 96, yaw_rate);
  291. _mav_put_float_array(buf, 48, vel_variance, 3);
  292. _mav_put_float_array(buf, 60, pos_variance, 3);
  293. _mav_put_float_array(buf, 72, q, 4);
  294. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
  295. #else
  296. mavlink_control_system_state_t packet;
  297. packet.time_usec = time_usec;
  298. packet.x_acc = x_acc;
  299. packet.y_acc = y_acc;
  300. packet.z_acc = z_acc;
  301. packet.x_vel = x_vel;
  302. packet.y_vel = y_vel;
  303. packet.z_vel = z_vel;
  304. packet.x_pos = x_pos;
  305. packet.y_pos = y_pos;
  306. packet.z_pos = z_pos;
  307. packet.airspeed = airspeed;
  308. packet.roll_rate = roll_rate;
  309. packet.pitch_rate = pitch_rate;
  310. packet.yaw_rate = yaw_rate;
  311. mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3);
  312. mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3);
  313. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  314. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
  315. #endif
  316. }
  317. /**
  318. * @brief Send a control_system_state message
  319. * @param chan MAVLink channel to send the message
  320. * @param struct The MAVLink struct to serialize
  321. */
  322. static inline void mavlink_msg_control_system_state_send_struct(mavlink_channel_t chan, const mavlink_control_system_state_t* control_system_state)
  323. {
  324. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  325. mavlink_msg_control_system_state_send(chan, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate);
  326. #else
  327. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)control_system_state, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
  328. #endif
  329. }
  330. #if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  331. /*
  332. This variant of _send() can be used to save stack space by re-using
  333. memory from the receive buffer. The caller provides a
  334. mavlink_message_t which is the size of a full mavlink message. This
  335. is usually the receive buffer for the channel, and allows a reply to an
  336. incoming message with minimum stack space usage.
  337. */
  338. static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate)
  339. {
  340. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  341. char *buf = (char *)msgbuf;
  342. _mav_put_uint64_t(buf, 0, time_usec);
  343. _mav_put_float(buf, 8, x_acc);
  344. _mav_put_float(buf, 12, y_acc);
  345. _mav_put_float(buf, 16, z_acc);
  346. _mav_put_float(buf, 20, x_vel);
  347. _mav_put_float(buf, 24, y_vel);
  348. _mav_put_float(buf, 28, z_vel);
  349. _mav_put_float(buf, 32, x_pos);
  350. _mav_put_float(buf, 36, y_pos);
  351. _mav_put_float(buf, 40, z_pos);
  352. _mav_put_float(buf, 44, airspeed);
  353. _mav_put_float(buf, 88, roll_rate);
  354. _mav_put_float(buf, 92, pitch_rate);
  355. _mav_put_float(buf, 96, yaw_rate);
  356. _mav_put_float_array(buf, 48, vel_variance, 3);
  357. _mav_put_float_array(buf, 60, pos_variance, 3);
  358. _mav_put_float_array(buf, 72, q, 4);
  359. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
  360. #else
  361. mavlink_control_system_state_t *packet = (mavlink_control_system_state_t *)msgbuf;
  362. packet->time_usec = time_usec;
  363. packet->x_acc = x_acc;
  364. packet->y_acc = y_acc;
  365. packet->z_acc = z_acc;
  366. packet->x_vel = x_vel;
  367. packet->y_vel = y_vel;
  368. packet->z_vel = z_vel;
  369. packet->x_pos = x_pos;
  370. packet->y_pos = y_pos;
  371. packet->z_pos = z_pos;
  372. packet->airspeed = airspeed;
  373. packet->roll_rate = roll_rate;
  374. packet->pitch_rate = pitch_rate;
  375. packet->yaw_rate = yaw_rate;
  376. mav_array_memcpy(packet->vel_variance, vel_variance, sizeof(float)*3);
  377. mav_array_memcpy(packet->pos_variance, pos_variance, sizeof(float)*3);
  378. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  379. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC);
  380. #endif
  381. }
  382. #endif
  383. #endif
  384. // MESSAGE CONTROL_SYSTEM_STATE UNPACKING
  385. /**
  386. * @brief Get field time_usec from control_system_state message
  387. *
  388. * @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.
  389. */
  390. static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg)
  391. {
  392. return _MAV_RETURN_uint64_t(msg, 0);
  393. }
  394. /**
  395. * @brief Get field x_acc from control_system_state message
  396. *
  397. * @return [m/s/s] X acceleration in body frame
  398. */
  399. static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg)
  400. {
  401. return _MAV_RETURN_float(msg, 8);
  402. }
  403. /**
  404. * @brief Get field y_acc from control_system_state message
  405. *
  406. * @return [m/s/s] Y acceleration in body frame
  407. */
  408. static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg)
  409. {
  410. return _MAV_RETURN_float(msg, 12);
  411. }
  412. /**
  413. * @brief Get field z_acc from control_system_state message
  414. *
  415. * @return [m/s/s] Z acceleration in body frame
  416. */
  417. static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg)
  418. {
  419. return _MAV_RETURN_float(msg, 16);
  420. }
  421. /**
  422. * @brief Get field x_vel from control_system_state message
  423. *
  424. * @return [m/s] X velocity in body frame
  425. */
  426. static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg)
  427. {
  428. return _MAV_RETURN_float(msg, 20);
  429. }
  430. /**
  431. * @brief Get field y_vel from control_system_state message
  432. *
  433. * @return [m/s] Y velocity in body frame
  434. */
  435. static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg)
  436. {
  437. return _MAV_RETURN_float(msg, 24);
  438. }
  439. /**
  440. * @brief Get field z_vel from control_system_state message
  441. *
  442. * @return [m/s] Z velocity in body frame
  443. */
  444. static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg)
  445. {
  446. return _MAV_RETURN_float(msg, 28);
  447. }
  448. /**
  449. * @brief Get field x_pos from control_system_state message
  450. *
  451. * @return [m] X position in local frame
  452. */
  453. static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg)
  454. {
  455. return _MAV_RETURN_float(msg, 32);
  456. }
  457. /**
  458. * @brief Get field y_pos from control_system_state message
  459. *
  460. * @return [m] Y position in local frame
  461. */
  462. static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg)
  463. {
  464. return _MAV_RETURN_float(msg, 36);
  465. }
  466. /**
  467. * @brief Get field z_pos from control_system_state message
  468. *
  469. * @return [m] Z position in local frame
  470. */
  471. static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg)
  472. {
  473. return _MAV_RETURN_float(msg, 40);
  474. }
  475. /**
  476. * @brief Get field airspeed from control_system_state message
  477. *
  478. * @return [m/s] Airspeed, set to -1 if unknown
  479. */
  480. static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg)
  481. {
  482. return _MAV_RETURN_float(msg, 44);
  483. }
  484. /**
  485. * @brief Get field vel_variance from control_system_state message
  486. *
  487. * @return Variance of body velocity estimate
  488. */
  489. static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance)
  490. {
  491. return _MAV_RETURN_float_array(msg, vel_variance, 3, 48);
  492. }
  493. /**
  494. * @brief Get field pos_variance from control_system_state message
  495. *
  496. * @return Variance in local position
  497. */
  498. static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance)
  499. {
  500. return _MAV_RETURN_float_array(msg, pos_variance, 3, 60);
  501. }
  502. /**
  503. * @brief Get field q from control_system_state message
  504. *
  505. * @return The attitude, represented as Quaternion
  506. */
  507. static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q)
  508. {
  509. return _MAV_RETURN_float_array(msg, q, 4, 72);
  510. }
  511. /**
  512. * @brief Get field roll_rate from control_system_state message
  513. *
  514. * @return [rad/s] Angular rate in roll axis
  515. */
  516. static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg)
  517. {
  518. return _MAV_RETURN_float(msg, 88);
  519. }
  520. /**
  521. * @brief Get field pitch_rate from control_system_state message
  522. *
  523. * @return [rad/s] Angular rate in pitch axis
  524. */
  525. static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg)
  526. {
  527. return _MAV_RETURN_float(msg, 92);
  528. }
  529. /**
  530. * @brief Get field yaw_rate from control_system_state message
  531. *
  532. * @return [rad/s] Angular rate in yaw axis
  533. */
  534. static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg)
  535. {
  536. return _MAV_RETURN_float(msg, 96);
  537. }
  538. /**
  539. * @brief Decode a control_system_state message into a struct
  540. *
  541. * @param msg The message to decode
  542. * @param control_system_state C-struct to decode the message contents into
  543. */
  544. static inline void mavlink_msg_control_system_state_decode(const mavlink_message_t* msg, mavlink_control_system_state_t* control_system_state)
  545. {
  546. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  547. control_system_state->time_usec = mavlink_msg_control_system_state_get_time_usec(msg);
  548. control_system_state->x_acc = mavlink_msg_control_system_state_get_x_acc(msg);
  549. control_system_state->y_acc = mavlink_msg_control_system_state_get_y_acc(msg);
  550. control_system_state->z_acc = mavlink_msg_control_system_state_get_z_acc(msg);
  551. control_system_state->x_vel = mavlink_msg_control_system_state_get_x_vel(msg);
  552. control_system_state->y_vel = mavlink_msg_control_system_state_get_y_vel(msg);
  553. control_system_state->z_vel = mavlink_msg_control_system_state_get_z_vel(msg);
  554. control_system_state->x_pos = mavlink_msg_control_system_state_get_x_pos(msg);
  555. control_system_state->y_pos = mavlink_msg_control_system_state_get_y_pos(msg);
  556. control_system_state->z_pos = mavlink_msg_control_system_state_get_z_pos(msg);
  557. control_system_state->airspeed = mavlink_msg_control_system_state_get_airspeed(msg);
  558. mavlink_msg_control_system_state_get_vel_variance(msg, control_system_state->vel_variance);
  559. mavlink_msg_control_system_state_get_pos_variance(msg, control_system_state->pos_variance);
  560. mavlink_msg_control_system_state_get_q(msg, control_system_state->q);
  561. control_system_state->roll_rate = mavlink_msg_control_system_state_get_roll_rate(msg);
  562. control_system_state->pitch_rate = mavlink_msg_control_system_state_get_pitch_rate(msg);
  563. control_system_state->yaw_rate = mavlink_msg_control_system_state_get_yaw_rate(msg);
  564. #else
  565. uint8_t len = msg->len < MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN? msg->len : MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN;
  566. memset(control_system_state, 0, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN);
  567. memcpy(control_system_state, _MAV_PAYLOAD(msg), len);
  568. #endif
  569. }