mavlink_msg_odometry.h 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632
  1. #pragma once
  2. // MESSAGE ODOMETRY PACKING
  3. #define MAVLINK_MSG_ID_ODOMETRY 331
  4. typedef struct __mavlink_odometry_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; /*< [m] X Position*/
  7. float y; /*< [m] Y Position*/
  8. float z; /*< [m] Z Position*/
  9. float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/
  10. float vx; /*< [m/s] X linear speed*/
  11. float vy; /*< [m/s] Y linear speed*/
  12. float vz; /*< [m/s] Z linear speed*/
  13. float rollspeed; /*< [rad/s] Roll angular speed*/
  14. float pitchspeed; /*< [rad/s] Pitch angular speed*/
  15. float yawspeed; /*< [rad/s] Yaw angular speed*/
  16. float pose_covariance[21]; /*< Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
  17. float velocity_covariance[21]; /*< Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
  18. uint8_t frame_id; /*< Coordinate frame of reference for the pose data.*/
  19. uint8_t child_frame_id; /*< Coordinate frame of reference for the velocity in free space (twist) data.*/
  20. uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/
  21. uint8_t estimator_type; /*< Type of estimator that is providing the odometry.*/
  22. int8_t quality; /*< [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality*/
  23. } mavlink_odometry_t;
  24. #define MAVLINK_MSG_ID_ODOMETRY_LEN 233
  25. #define MAVLINK_MSG_ID_ODOMETRY_MIN_LEN 230
  26. #define MAVLINK_MSG_ID_331_LEN 233
  27. #define MAVLINK_MSG_ID_331_MIN_LEN 230
  28. #define MAVLINK_MSG_ID_ODOMETRY_CRC 91
  29. #define MAVLINK_MSG_ID_331_CRC 91
  30. #define MAVLINK_MSG_ODOMETRY_FIELD_Q_LEN 4
  31. #define MAVLINK_MSG_ODOMETRY_FIELD_POSE_COVARIANCE_LEN 21
  32. #define MAVLINK_MSG_ODOMETRY_FIELD_VELOCITY_COVARIANCE_LEN 21
  33. #if MAVLINK_COMMAND_24BIT
  34. #define MAVLINK_MESSAGE_INFO_ODOMETRY { \
  35. 331, \
  36. "ODOMETRY", \
  37. 18, \
  38. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_odometry_t, time_usec) }, \
  39. { "frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_odometry_t, frame_id) }, \
  40. { "child_frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 229, offsetof(mavlink_odometry_t, child_frame_id) }, \
  41. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_odometry_t, x) }, \
  42. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_odometry_t, y) }, \
  43. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_odometry_t, z) }, \
  44. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_odometry_t, q) }, \
  45. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_odometry_t, vx) }, \
  46. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_odometry_t, vy) }, \
  47. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_odometry_t, vz) }, \
  48. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_odometry_t, rollspeed) }, \
  49. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_odometry_t, pitchspeed) }, \
  50. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_odometry_t, yawspeed) }, \
  51. { "pose_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 60, offsetof(mavlink_odometry_t, pose_covariance) }, \
  52. { "velocity_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 144, offsetof(mavlink_odometry_t, velocity_covariance) }, \
  53. { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 230, offsetof(mavlink_odometry_t, reset_counter) }, \
  54. { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 231, offsetof(mavlink_odometry_t, estimator_type) }, \
  55. { "quality", NULL, MAVLINK_TYPE_INT8_T, 0, 232, offsetof(mavlink_odometry_t, quality) }, \
  56. } \
  57. }
  58. #else
  59. #define MAVLINK_MESSAGE_INFO_ODOMETRY { \
  60. "ODOMETRY", \
  61. 18, \
  62. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_odometry_t, time_usec) }, \
  63. { "frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_odometry_t, frame_id) }, \
  64. { "child_frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 229, offsetof(mavlink_odometry_t, child_frame_id) }, \
  65. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_odometry_t, x) }, \
  66. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_odometry_t, y) }, \
  67. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_odometry_t, z) }, \
  68. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_odometry_t, q) }, \
  69. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_odometry_t, vx) }, \
  70. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_odometry_t, vy) }, \
  71. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_odometry_t, vz) }, \
  72. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_odometry_t, rollspeed) }, \
  73. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_odometry_t, pitchspeed) }, \
  74. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_odometry_t, yawspeed) }, \
  75. { "pose_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 60, offsetof(mavlink_odometry_t, pose_covariance) }, \
  76. { "velocity_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 144, offsetof(mavlink_odometry_t, velocity_covariance) }, \
  77. { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 230, offsetof(mavlink_odometry_t, reset_counter) }, \
  78. { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 231, offsetof(mavlink_odometry_t, estimator_type) }, \
  79. { "quality", NULL, MAVLINK_TYPE_INT8_T, 0, 232, offsetof(mavlink_odometry_t, quality) }, \
  80. } \
  81. }
  82. #endif
  83. /**
  84. * @brief Pack a odometry message
  85. * @param system_id ID of this system
  86. * @param component_id ID of this component (e.g. 200 for IMU)
  87. * @param msg The MAVLink message to compress the data into
  88. *
  89. * @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.
  90. * @param frame_id Coordinate frame of reference for the pose data.
  91. * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
  92. * @param x [m] X Position
  93. * @param y [m] Y Position
  94. * @param z [m] Z Position
  95. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  96. * @param vx [m/s] X linear speed
  97. * @param vy [m/s] Y linear speed
  98. * @param vz [m/s] Z linear speed
  99. * @param rollspeed [rad/s] Roll angular speed
  100. * @param pitchspeed [rad/s] Pitch angular speed
  101. * @param yawspeed [rad/s] Yaw angular speed
  102. * @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  103. * @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  104. * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  105. * @param estimator_type Type of estimator that is providing the odometry.
  106. * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  107. * @return length of the message in bytes (excluding serial stream start sign)
  108. */
  109. static inline uint16_t mavlink_msg_odometry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  110. uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type, int8_t quality)
  111. {
  112. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  113. char buf[MAVLINK_MSG_ID_ODOMETRY_LEN];
  114. _mav_put_uint64_t(buf, 0, time_usec);
  115. _mav_put_float(buf, 8, x);
  116. _mav_put_float(buf, 12, y);
  117. _mav_put_float(buf, 16, z);
  118. _mav_put_float(buf, 36, vx);
  119. _mav_put_float(buf, 40, vy);
  120. _mav_put_float(buf, 44, vz);
  121. _mav_put_float(buf, 48, rollspeed);
  122. _mav_put_float(buf, 52, pitchspeed);
  123. _mav_put_float(buf, 56, yawspeed);
  124. _mav_put_uint8_t(buf, 228, frame_id);
  125. _mav_put_uint8_t(buf, 229, child_frame_id);
  126. _mav_put_uint8_t(buf, 230, reset_counter);
  127. _mav_put_uint8_t(buf, 231, estimator_type);
  128. _mav_put_int8_t(buf, 232, quality);
  129. _mav_put_float_array(buf, 20, q, 4);
  130. _mav_put_float_array(buf, 60, pose_covariance, 21);
  131. _mav_put_float_array(buf, 144, velocity_covariance, 21);
  132. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ODOMETRY_LEN);
  133. #else
  134. mavlink_odometry_t packet;
  135. packet.time_usec = time_usec;
  136. packet.x = x;
  137. packet.y = y;
  138. packet.z = z;
  139. packet.vx = vx;
  140. packet.vy = vy;
  141. packet.vz = vz;
  142. packet.rollspeed = rollspeed;
  143. packet.pitchspeed = pitchspeed;
  144. packet.yawspeed = yawspeed;
  145. packet.frame_id = frame_id;
  146. packet.child_frame_id = child_frame_id;
  147. packet.reset_counter = reset_counter;
  148. packet.estimator_type = estimator_type;
  149. packet.quality = quality;
  150. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  151. mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
  152. mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
  153. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ODOMETRY_LEN);
  154. #endif
  155. msg->msgid = MAVLINK_MSG_ID_ODOMETRY;
  156. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  157. }
  158. /**
  159. * @brief Pack a odometry message on a channel
  160. * @param system_id ID of this system
  161. * @param component_id ID of this component (e.g. 200 for IMU)
  162. * @param chan The MAVLink channel this message will be sent over
  163. * @param msg The MAVLink message to compress the data into
  164. * @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.
  165. * @param frame_id Coordinate frame of reference for the pose data.
  166. * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
  167. * @param x [m] X Position
  168. * @param y [m] Y Position
  169. * @param z [m] Z Position
  170. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  171. * @param vx [m/s] X linear speed
  172. * @param vy [m/s] Y linear speed
  173. * @param vz [m/s] Z linear speed
  174. * @param rollspeed [rad/s] Roll angular speed
  175. * @param pitchspeed [rad/s] Pitch angular speed
  176. * @param yawspeed [rad/s] Yaw angular speed
  177. * @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  178. * @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  179. * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  180. * @param estimator_type Type of estimator that is providing the odometry.
  181. * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  182. * @return length of the message in bytes (excluding serial stream start sign)
  183. */
  184. static inline uint16_t mavlink_msg_odometry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  185. mavlink_message_t* msg,
  186. uint64_t time_usec,uint8_t frame_id,uint8_t child_frame_id,float x,float y,float z,const float *q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,const float *pose_covariance,const float *velocity_covariance,uint8_t reset_counter,uint8_t estimator_type,int8_t quality)
  187. {
  188. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  189. char buf[MAVLINK_MSG_ID_ODOMETRY_LEN];
  190. _mav_put_uint64_t(buf, 0, time_usec);
  191. _mav_put_float(buf, 8, x);
  192. _mav_put_float(buf, 12, y);
  193. _mav_put_float(buf, 16, z);
  194. _mav_put_float(buf, 36, vx);
  195. _mav_put_float(buf, 40, vy);
  196. _mav_put_float(buf, 44, vz);
  197. _mav_put_float(buf, 48, rollspeed);
  198. _mav_put_float(buf, 52, pitchspeed);
  199. _mav_put_float(buf, 56, yawspeed);
  200. _mav_put_uint8_t(buf, 228, frame_id);
  201. _mav_put_uint8_t(buf, 229, child_frame_id);
  202. _mav_put_uint8_t(buf, 230, reset_counter);
  203. _mav_put_uint8_t(buf, 231, estimator_type);
  204. _mav_put_int8_t(buf, 232, quality);
  205. _mav_put_float_array(buf, 20, q, 4);
  206. _mav_put_float_array(buf, 60, pose_covariance, 21);
  207. _mav_put_float_array(buf, 144, velocity_covariance, 21);
  208. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ODOMETRY_LEN);
  209. #else
  210. mavlink_odometry_t packet;
  211. packet.time_usec = time_usec;
  212. packet.x = x;
  213. packet.y = y;
  214. packet.z = z;
  215. packet.vx = vx;
  216. packet.vy = vy;
  217. packet.vz = vz;
  218. packet.rollspeed = rollspeed;
  219. packet.pitchspeed = pitchspeed;
  220. packet.yawspeed = yawspeed;
  221. packet.frame_id = frame_id;
  222. packet.child_frame_id = child_frame_id;
  223. packet.reset_counter = reset_counter;
  224. packet.estimator_type = estimator_type;
  225. packet.quality = quality;
  226. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  227. mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
  228. mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
  229. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ODOMETRY_LEN);
  230. #endif
  231. msg->msgid = MAVLINK_MSG_ID_ODOMETRY;
  232. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  233. }
  234. /**
  235. * @brief Encode a odometry struct
  236. *
  237. * @param system_id ID of this system
  238. * @param component_id ID of this component (e.g. 200 for IMU)
  239. * @param msg The MAVLink message to compress the data into
  240. * @param odometry C-struct to read the message contents from
  241. */
  242. static inline uint16_t mavlink_msg_odometry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_odometry_t* odometry)
  243. {
  244. return mavlink_msg_odometry_pack(system_id, component_id, msg, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type, odometry->quality);
  245. }
  246. /**
  247. * @brief Encode a odometry struct on a channel
  248. *
  249. * @param system_id ID of this system
  250. * @param component_id ID of this component (e.g. 200 for IMU)
  251. * @param chan The MAVLink channel this message will be sent over
  252. * @param msg The MAVLink message to compress the data into
  253. * @param odometry C-struct to read the message contents from
  254. */
  255. static inline uint16_t mavlink_msg_odometry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_odometry_t* odometry)
  256. {
  257. return mavlink_msg_odometry_pack_chan(system_id, component_id, chan, msg, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type, odometry->quality);
  258. }
  259. /**
  260. * @brief Send a odometry message
  261. * @param chan MAVLink channel to send the message
  262. *
  263. * @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.
  264. * @param frame_id Coordinate frame of reference for the pose data.
  265. * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
  266. * @param x [m] X Position
  267. * @param y [m] Y Position
  268. * @param z [m] Z Position
  269. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  270. * @param vx [m/s] X linear speed
  271. * @param vy [m/s] Y linear speed
  272. * @param vz [m/s] Z linear speed
  273. * @param rollspeed [rad/s] Roll angular speed
  274. * @param pitchspeed [rad/s] Pitch angular speed
  275. * @param yawspeed [rad/s] Yaw angular speed
  276. * @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  277. * @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  278. * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  279. * @param estimator_type Type of estimator that is providing the odometry.
  280. * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  281. */
  282. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  283. static inline void mavlink_msg_odometry_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type, int8_t quality)
  284. {
  285. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  286. char buf[MAVLINK_MSG_ID_ODOMETRY_LEN];
  287. _mav_put_uint64_t(buf, 0, time_usec);
  288. _mav_put_float(buf, 8, x);
  289. _mav_put_float(buf, 12, y);
  290. _mav_put_float(buf, 16, z);
  291. _mav_put_float(buf, 36, vx);
  292. _mav_put_float(buf, 40, vy);
  293. _mav_put_float(buf, 44, vz);
  294. _mav_put_float(buf, 48, rollspeed);
  295. _mav_put_float(buf, 52, pitchspeed);
  296. _mav_put_float(buf, 56, yawspeed);
  297. _mav_put_uint8_t(buf, 228, frame_id);
  298. _mav_put_uint8_t(buf, 229, child_frame_id);
  299. _mav_put_uint8_t(buf, 230, reset_counter);
  300. _mav_put_uint8_t(buf, 231, estimator_type);
  301. _mav_put_int8_t(buf, 232, quality);
  302. _mav_put_float_array(buf, 20, q, 4);
  303. _mav_put_float_array(buf, 60, pose_covariance, 21);
  304. _mav_put_float_array(buf, 144, velocity_covariance, 21);
  305. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, buf, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  306. #else
  307. mavlink_odometry_t packet;
  308. packet.time_usec = time_usec;
  309. packet.x = x;
  310. packet.y = y;
  311. packet.z = z;
  312. packet.vx = vx;
  313. packet.vy = vy;
  314. packet.vz = vz;
  315. packet.rollspeed = rollspeed;
  316. packet.pitchspeed = pitchspeed;
  317. packet.yawspeed = yawspeed;
  318. packet.frame_id = frame_id;
  319. packet.child_frame_id = child_frame_id;
  320. packet.reset_counter = reset_counter;
  321. packet.estimator_type = estimator_type;
  322. packet.quality = quality;
  323. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  324. mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
  325. mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
  326. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)&packet, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  327. #endif
  328. }
  329. /**
  330. * @brief Send a odometry message
  331. * @param chan MAVLink channel to send the message
  332. * @param struct The MAVLink struct to serialize
  333. */
  334. static inline void mavlink_msg_odometry_send_struct(mavlink_channel_t chan, const mavlink_odometry_t* odometry)
  335. {
  336. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  337. mavlink_msg_odometry_send(chan, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type, odometry->quality);
  338. #else
  339. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)odometry, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  340. #endif
  341. }
  342. #if MAVLINK_MSG_ID_ODOMETRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  343. /*
  344. This variant of _send() can be used to save stack space by re-using
  345. memory from the receive buffer. The caller provides a
  346. mavlink_message_t which is the size of a full mavlink message. This
  347. is usually the receive buffer for the channel, and allows a reply to an
  348. incoming message with minimum stack space usage.
  349. */
  350. static inline void mavlink_msg_odometry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type, int8_t quality)
  351. {
  352. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  353. char *buf = (char *)msgbuf;
  354. _mav_put_uint64_t(buf, 0, time_usec);
  355. _mav_put_float(buf, 8, x);
  356. _mav_put_float(buf, 12, y);
  357. _mav_put_float(buf, 16, z);
  358. _mav_put_float(buf, 36, vx);
  359. _mav_put_float(buf, 40, vy);
  360. _mav_put_float(buf, 44, vz);
  361. _mav_put_float(buf, 48, rollspeed);
  362. _mav_put_float(buf, 52, pitchspeed);
  363. _mav_put_float(buf, 56, yawspeed);
  364. _mav_put_uint8_t(buf, 228, frame_id);
  365. _mav_put_uint8_t(buf, 229, child_frame_id);
  366. _mav_put_uint8_t(buf, 230, reset_counter);
  367. _mav_put_uint8_t(buf, 231, estimator_type);
  368. _mav_put_int8_t(buf, 232, quality);
  369. _mav_put_float_array(buf, 20, q, 4);
  370. _mav_put_float_array(buf, 60, pose_covariance, 21);
  371. _mav_put_float_array(buf, 144, velocity_covariance, 21);
  372. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, buf, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  373. #else
  374. mavlink_odometry_t *packet = (mavlink_odometry_t *)msgbuf;
  375. packet->time_usec = time_usec;
  376. packet->x = x;
  377. packet->y = y;
  378. packet->z = z;
  379. packet->vx = vx;
  380. packet->vy = vy;
  381. packet->vz = vz;
  382. packet->rollspeed = rollspeed;
  383. packet->pitchspeed = pitchspeed;
  384. packet->yawspeed = yawspeed;
  385. packet->frame_id = frame_id;
  386. packet->child_frame_id = child_frame_id;
  387. packet->reset_counter = reset_counter;
  388. packet->estimator_type = estimator_type;
  389. packet->quality = quality;
  390. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  391. mav_array_memcpy(packet->pose_covariance, pose_covariance, sizeof(float)*21);
  392. mav_array_memcpy(packet->velocity_covariance, velocity_covariance, sizeof(float)*21);
  393. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)packet, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  394. #endif
  395. }
  396. #endif
  397. #endif
  398. // MESSAGE ODOMETRY UNPACKING
  399. /**
  400. * @brief Get field time_usec from odometry message
  401. *
  402. * @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.
  403. */
  404. static inline uint64_t mavlink_msg_odometry_get_time_usec(const mavlink_message_t* msg)
  405. {
  406. return _MAV_RETURN_uint64_t(msg, 0);
  407. }
  408. /**
  409. * @brief Get field frame_id from odometry message
  410. *
  411. * @return Coordinate frame of reference for the pose data.
  412. */
  413. static inline uint8_t mavlink_msg_odometry_get_frame_id(const mavlink_message_t* msg)
  414. {
  415. return _MAV_RETURN_uint8_t(msg, 228);
  416. }
  417. /**
  418. * @brief Get field child_frame_id from odometry message
  419. *
  420. * @return Coordinate frame of reference for the velocity in free space (twist) data.
  421. */
  422. static inline uint8_t mavlink_msg_odometry_get_child_frame_id(const mavlink_message_t* msg)
  423. {
  424. return _MAV_RETURN_uint8_t(msg, 229);
  425. }
  426. /**
  427. * @brief Get field x from odometry message
  428. *
  429. * @return [m] X Position
  430. */
  431. static inline float mavlink_msg_odometry_get_x(const mavlink_message_t* msg)
  432. {
  433. return _MAV_RETURN_float(msg, 8);
  434. }
  435. /**
  436. * @brief Get field y from odometry message
  437. *
  438. * @return [m] Y Position
  439. */
  440. static inline float mavlink_msg_odometry_get_y(const mavlink_message_t* msg)
  441. {
  442. return _MAV_RETURN_float(msg, 12);
  443. }
  444. /**
  445. * @brief Get field z from odometry message
  446. *
  447. * @return [m] Z Position
  448. */
  449. static inline float mavlink_msg_odometry_get_z(const mavlink_message_t* msg)
  450. {
  451. return _MAV_RETURN_float(msg, 16);
  452. }
  453. /**
  454. * @brief Get field q from odometry message
  455. *
  456. * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  457. */
  458. static inline uint16_t mavlink_msg_odometry_get_q(const mavlink_message_t* msg, float *q)
  459. {
  460. return _MAV_RETURN_float_array(msg, q, 4, 20);
  461. }
  462. /**
  463. * @brief Get field vx from odometry message
  464. *
  465. * @return [m/s] X linear speed
  466. */
  467. static inline float mavlink_msg_odometry_get_vx(const mavlink_message_t* msg)
  468. {
  469. return _MAV_RETURN_float(msg, 36);
  470. }
  471. /**
  472. * @brief Get field vy from odometry message
  473. *
  474. * @return [m/s] Y linear speed
  475. */
  476. static inline float mavlink_msg_odometry_get_vy(const mavlink_message_t* msg)
  477. {
  478. return _MAV_RETURN_float(msg, 40);
  479. }
  480. /**
  481. * @brief Get field vz from odometry message
  482. *
  483. * @return [m/s] Z linear speed
  484. */
  485. static inline float mavlink_msg_odometry_get_vz(const mavlink_message_t* msg)
  486. {
  487. return _MAV_RETURN_float(msg, 44);
  488. }
  489. /**
  490. * @brief Get field rollspeed from odometry message
  491. *
  492. * @return [rad/s] Roll angular speed
  493. */
  494. static inline float mavlink_msg_odometry_get_rollspeed(const mavlink_message_t* msg)
  495. {
  496. return _MAV_RETURN_float(msg, 48);
  497. }
  498. /**
  499. * @brief Get field pitchspeed from odometry message
  500. *
  501. * @return [rad/s] Pitch angular speed
  502. */
  503. static inline float mavlink_msg_odometry_get_pitchspeed(const mavlink_message_t* msg)
  504. {
  505. return _MAV_RETURN_float(msg, 52);
  506. }
  507. /**
  508. * @brief Get field yawspeed from odometry message
  509. *
  510. * @return [rad/s] Yaw angular speed
  511. */
  512. static inline float mavlink_msg_odometry_get_yawspeed(const mavlink_message_t* msg)
  513. {
  514. return _MAV_RETURN_float(msg, 56);
  515. }
  516. /**
  517. * @brief Get field pose_covariance from odometry message
  518. *
  519. * @return Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  520. */
  521. static inline uint16_t mavlink_msg_odometry_get_pose_covariance(const mavlink_message_t* msg, float *pose_covariance)
  522. {
  523. return _MAV_RETURN_float_array(msg, pose_covariance, 21, 60);
  524. }
  525. /**
  526. * @brief Get field velocity_covariance from odometry message
  527. *
  528. * @return Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  529. */
  530. static inline uint16_t mavlink_msg_odometry_get_velocity_covariance(const mavlink_message_t* msg, float *velocity_covariance)
  531. {
  532. return _MAV_RETURN_float_array(msg, velocity_covariance, 21, 144);
  533. }
  534. /**
  535. * @brief Get field reset_counter from odometry message
  536. *
  537. * @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  538. */
  539. static inline uint8_t mavlink_msg_odometry_get_reset_counter(const mavlink_message_t* msg)
  540. {
  541. return _MAV_RETURN_uint8_t(msg, 230);
  542. }
  543. /**
  544. * @brief Get field estimator_type from odometry message
  545. *
  546. * @return Type of estimator that is providing the odometry.
  547. */
  548. static inline uint8_t mavlink_msg_odometry_get_estimator_type(const mavlink_message_t* msg)
  549. {
  550. return _MAV_RETURN_uint8_t(msg, 231);
  551. }
  552. /**
  553. * @brief Get field quality from odometry message
  554. *
  555. * @return [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  556. */
  557. static inline int8_t mavlink_msg_odometry_get_quality(const mavlink_message_t* msg)
  558. {
  559. return _MAV_RETURN_int8_t(msg, 232);
  560. }
  561. /**
  562. * @brief Decode a odometry message into a struct
  563. *
  564. * @param msg The message to decode
  565. * @param odometry C-struct to decode the message contents into
  566. */
  567. static inline void mavlink_msg_odometry_decode(const mavlink_message_t* msg, mavlink_odometry_t* odometry)
  568. {
  569. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  570. odometry->time_usec = mavlink_msg_odometry_get_time_usec(msg);
  571. odometry->x = mavlink_msg_odometry_get_x(msg);
  572. odometry->y = mavlink_msg_odometry_get_y(msg);
  573. odometry->z = mavlink_msg_odometry_get_z(msg);
  574. mavlink_msg_odometry_get_q(msg, odometry->q);
  575. odometry->vx = mavlink_msg_odometry_get_vx(msg);
  576. odometry->vy = mavlink_msg_odometry_get_vy(msg);
  577. odometry->vz = mavlink_msg_odometry_get_vz(msg);
  578. odometry->rollspeed = mavlink_msg_odometry_get_rollspeed(msg);
  579. odometry->pitchspeed = mavlink_msg_odometry_get_pitchspeed(msg);
  580. odometry->yawspeed = mavlink_msg_odometry_get_yawspeed(msg);
  581. mavlink_msg_odometry_get_pose_covariance(msg, odometry->pose_covariance);
  582. mavlink_msg_odometry_get_velocity_covariance(msg, odometry->velocity_covariance);
  583. odometry->frame_id = mavlink_msg_odometry_get_frame_id(msg);
  584. odometry->child_frame_id = mavlink_msg_odometry_get_child_frame_id(msg);
  585. odometry->reset_counter = mavlink_msg_odometry_get_reset_counter(msg);
  586. odometry->estimator_type = mavlink_msg_odometry_get_estimator_type(msg);
  587. odometry->quality = mavlink_msg_odometry_get_quality(msg);
  588. #else
  589. uint8_t len = msg->len < MAVLINK_MSG_ID_ODOMETRY_LEN? msg->len : MAVLINK_MSG_ID_ODOMETRY_LEN;
  590. memset(odometry, 0, MAVLINK_MSG_ID_ODOMETRY_LEN);
  591. memcpy(odometry, _MAV_PAYLOAD(msg), len);
  592. #endif
  593. }