2
0

mavlink_msg_odometry.h 37 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728
  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
  160. * @param system_id ID of this system
  161. * @param component_id ID of this component (e.g. 200 for IMU)
  162. * @param status MAVLink status structure
  163. * @param msg The MAVLink message to compress the data into
  164. *
  165. * @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.
  166. * @param frame_id Coordinate frame of reference for the pose data.
  167. * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
  168. * @param x [m] X Position
  169. * @param y [m] Y Position
  170. * @param z [m] Z Position
  171. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  172. * @param vx [m/s] X linear speed
  173. * @param vy [m/s] Y linear speed
  174. * @param vz [m/s] Z linear speed
  175. * @param rollspeed [rad/s] Roll angular speed
  176. * @param pitchspeed [rad/s] Pitch angular speed
  177. * @param yawspeed [rad/s] Yaw angular speed
  178. * @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.
  179. * @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.
  180. * @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.
  181. * @param estimator_type Type of estimator that is providing the odometry.
  182. * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  183. * @return length of the message in bytes (excluding serial stream start sign)
  184. */
  185. static inline uint16_t mavlink_msg_odometry_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  233. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
  234. #else
  235. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN);
  236. #endif
  237. }
  238. /**
  239. * @brief Pack a odometry message on a channel
  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 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.
  245. * @param frame_id Coordinate frame of reference for the pose data.
  246. * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
  247. * @param x [m] X Position
  248. * @param y [m] Y Position
  249. * @param z [m] Z Position
  250. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  251. * @param vx [m/s] X linear speed
  252. * @param vy [m/s] Y linear speed
  253. * @param vz [m/s] Z linear speed
  254. * @param rollspeed [rad/s] Roll angular speed
  255. * @param pitchspeed [rad/s] Pitch angular speed
  256. * @param yawspeed [rad/s] Yaw angular speed
  257. * @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.
  258. * @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.
  259. * @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.
  260. * @param estimator_type Type of estimator that is providing the odometry.
  261. * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  262. * @return length of the message in bytes (excluding serial stream start sign)
  263. */
  264. static inline uint16_t mavlink_msg_odometry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  265. mavlink_message_t* msg,
  266. 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)
  267. {
  268. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  269. char buf[MAVLINK_MSG_ID_ODOMETRY_LEN];
  270. _mav_put_uint64_t(buf, 0, time_usec);
  271. _mav_put_float(buf, 8, x);
  272. _mav_put_float(buf, 12, y);
  273. _mav_put_float(buf, 16, z);
  274. _mav_put_float(buf, 36, vx);
  275. _mav_put_float(buf, 40, vy);
  276. _mav_put_float(buf, 44, vz);
  277. _mav_put_float(buf, 48, rollspeed);
  278. _mav_put_float(buf, 52, pitchspeed);
  279. _mav_put_float(buf, 56, yawspeed);
  280. _mav_put_uint8_t(buf, 228, frame_id);
  281. _mav_put_uint8_t(buf, 229, child_frame_id);
  282. _mav_put_uint8_t(buf, 230, reset_counter);
  283. _mav_put_uint8_t(buf, 231, estimator_type);
  284. _mav_put_int8_t(buf, 232, quality);
  285. _mav_put_float_array(buf, 20, q, 4);
  286. _mav_put_float_array(buf, 60, pose_covariance, 21);
  287. _mav_put_float_array(buf, 144, velocity_covariance, 21);
  288. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ODOMETRY_LEN);
  289. #else
  290. mavlink_odometry_t packet;
  291. packet.time_usec = time_usec;
  292. packet.x = x;
  293. packet.y = y;
  294. packet.z = z;
  295. packet.vx = vx;
  296. packet.vy = vy;
  297. packet.vz = vz;
  298. packet.rollspeed = rollspeed;
  299. packet.pitchspeed = pitchspeed;
  300. packet.yawspeed = yawspeed;
  301. packet.frame_id = frame_id;
  302. packet.child_frame_id = child_frame_id;
  303. packet.reset_counter = reset_counter;
  304. packet.estimator_type = estimator_type;
  305. packet.quality = quality;
  306. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  307. mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
  308. mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
  309. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ODOMETRY_LEN);
  310. #endif
  311. msg->msgid = MAVLINK_MSG_ID_ODOMETRY;
  312. 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);
  313. }
  314. /**
  315. * @brief Encode a odometry struct
  316. *
  317. * @param system_id ID of this system
  318. * @param component_id ID of this component (e.g. 200 for IMU)
  319. * @param msg The MAVLink message to compress the data into
  320. * @param odometry C-struct to read the message contents from
  321. */
  322. 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)
  323. {
  324. 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);
  325. }
  326. /**
  327. * @brief Encode a odometry struct on a channel
  328. *
  329. * @param system_id ID of this system
  330. * @param component_id ID of this component (e.g. 200 for IMU)
  331. * @param chan The MAVLink channel this message will be sent over
  332. * @param msg The MAVLink message to compress the data into
  333. * @param odometry C-struct to read the message contents from
  334. */
  335. 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)
  336. {
  337. 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);
  338. }
  339. /**
  340. * @brief Encode a odometry struct with provided status structure
  341. *
  342. * @param system_id ID of this system
  343. * @param component_id ID of this component (e.g. 200 for IMU)
  344. * @param status MAVLink status structure
  345. * @param msg The MAVLink message to compress the data into
  346. * @param odometry C-struct to read the message contents from
  347. */
  348. static inline uint16_t mavlink_msg_odometry_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_odometry_t* odometry)
  349. {
  350. return mavlink_msg_odometry_pack_status(system_id, component_id, _status, 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);
  351. }
  352. /**
  353. * @brief Send a odometry message
  354. * @param chan MAVLink channel to send the message
  355. *
  356. * @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.
  357. * @param frame_id Coordinate frame of reference for the pose data.
  358. * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
  359. * @param x [m] X Position
  360. * @param y [m] Y Position
  361. * @param z [m] Z Position
  362. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  363. * @param vx [m/s] X linear speed
  364. * @param vy [m/s] Y linear speed
  365. * @param vz [m/s] Z linear speed
  366. * @param rollspeed [rad/s] Roll angular speed
  367. * @param pitchspeed [rad/s] Pitch angular speed
  368. * @param yawspeed [rad/s] Yaw angular speed
  369. * @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.
  370. * @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.
  371. * @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.
  372. * @param estimator_type Type of estimator that is providing the odometry.
  373. * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  374. */
  375. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  376. 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)
  377. {
  378. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  379. char buf[MAVLINK_MSG_ID_ODOMETRY_LEN];
  380. _mav_put_uint64_t(buf, 0, time_usec);
  381. _mav_put_float(buf, 8, x);
  382. _mav_put_float(buf, 12, y);
  383. _mav_put_float(buf, 16, z);
  384. _mav_put_float(buf, 36, vx);
  385. _mav_put_float(buf, 40, vy);
  386. _mav_put_float(buf, 44, vz);
  387. _mav_put_float(buf, 48, rollspeed);
  388. _mav_put_float(buf, 52, pitchspeed);
  389. _mav_put_float(buf, 56, yawspeed);
  390. _mav_put_uint8_t(buf, 228, frame_id);
  391. _mav_put_uint8_t(buf, 229, child_frame_id);
  392. _mav_put_uint8_t(buf, 230, reset_counter);
  393. _mav_put_uint8_t(buf, 231, estimator_type);
  394. _mav_put_int8_t(buf, 232, quality);
  395. _mav_put_float_array(buf, 20, q, 4);
  396. _mav_put_float_array(buf, 60, pose_covariance, 21);
  397. _mav_put_float_array(buf, 144, velocity_covariance, 21);
  398. _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);
  399. #else
  400. mavlink_odometry_t packet;
  401. packet.time_usec = time_usec;
  402. packet.x = x;
  403. packet.y = y;
  404. packet.z = z;
  405. packet.vx = vx;
  406. packet.vy = vy;
  407. packet.vz = vz;
  408. packet.rollspeed = rollspeed;
  409. packet.pitchspeed = pitchspeed;
  410. packet.yawspeed = yawspeed;
  411. packet.frame_id = frame_id;
  412. packet.child_frame_id = child_frame_id;
  413. packet.reset_counter = reset_counter;
  414. packet.estimator_type = estimator_type;
  415. packet.quality = quality;
  416. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  417. mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
  418. mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
  419. _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);
  420. #endif
  421. }
  422. /**
  423. * @brief Send a odometry message
  424. * @param chan MAVLink channel to send the message
  425. * @param struct The MAVLink struct to serialize
  426. */
  427. static inline void mavlink_msg_odometry_send_struct(mavlink_channel_t chan, const mavlink_odometry_t* odometry)
  428. {
  429. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  430. 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);
  431. #else
  432. _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);
  433. #endif
  434. }
  435. #if MAVLINK_MSG_ID_ODOMETRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  436. /*
  437. This variant of _send() can be used to save stack space by re-using
  438. memory from the receive buffer. The caller provides a
  439. mavlink_message_t which is the size of a full mavlink message. This
  440. is usually the receive buffer for the channel, and allows a reply to an
  441. incoming message with minimum stack space usage.
  442. */
  443. 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)
  444. {
  445. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  446. char *buf = (char *)msgbuf;
  447. _mav_put_uint64_t(buf, 0, time_usec);
  448. _mav_put_float(buf, 8, x);
  449. _mav_put_float(buf, 12, y);
  450. _mav_put_float(buf, 16, z);
  451. _mav_put_float(buf, 36, vx);
  452. _mav_put_float(buf, 40, vy);
  453. _mav_put_float(buf, 44, vz);
  454. _mav_put_float(buf, 48, rollspeed);
  455. _mav_put_float(buf, 52, pitchspeed);
  456. _mav_put_float(buf, 56, yawspeed);
  457. _mav_put_uint8_t(buf, 228, frame_id);
  458. _mav_put_uint8_t(buf, 229, child_frame_id);
  459. _mav_put_uint8_t(buf, 230, reset_counter);
  460. _mav_put_uint8_t(buf, 231, estimator_type);
  461. _mav_put_int8_t(buf, 232, quality);
  462. _mav_put_float_array(buf, 20, q, 4);
  463. _mav_put_float_array(buf, 60, pose_covariance, 21);
  464. _mav_put_float_array(buf, 144, velocity_covariance, 21);
  465. _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);
  466. #else
  467. mavlink_odometry_t *packet = (mavlink_odometry_t *)msgbuf;
  468. packet->time_usec = time_usec;
  469. packet->x = x;
  470. packet->y = y;
  471. packet->z = z;
  472. packet->vx = vx;
  473. packet->vy = vy;
  474. packet->vz = vz;
  475. packet->rollspeed = rollspeed;
  476. packet->pitchspeed = pitchspeed;
  477. packet->yawspeed = yawspeed;
  478. packet->frame_id = frame_id;
  479. packet->child_frame_id = child_frame_id;
  480. packet->reset_counter = reset_counter;
  481. packet->estimator_type = estimator_type;
  482. packet->quality = quality;
  483. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  484. mav_array_memcpy(packet->pose_covariance, pose_covariance, sizeof(float)*21);
  485. mav_array_memcpy(packet->velocity_covariance, velocity_covariance, sizeof(float)*21);
  486. _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);
  487. #endif
  488. }
  489. #endif
  490. #endif
  491. // MESSAGE ODOMETRY UNPACKING
  492. /**
  493. * @brief Get field time_usec from odometry message
  494. *
  495. * @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.
  496. */
  497. static inline uint64_t mavlink_msg_odometry_get_time_usec(const mavlink_message_t* msg)
  498. {
  499. return _MAV_RETURN_uint64_t(msg, 0);
  500. }
  501. /**
  502. * @brief Get field frame_id from odometry message
  503. *
  504. * @return Coordinate frame of reference for the pose data.
  505. */
  506. static inline uint8_t mavlink_msg_odometry_get_frame_id(const mavlink_message_t* msg)
  507. {
  508. return _MAV_RETURN_uint8_t(msg, 228);
  509. }
  510. /**
  511. * @brief Get field child_frame_id from odometry message
  512. *
  513. * @return Coordinate frame of reference for the velocity in free space (twist) data.
  514. */
  515. static inline uint8_t mavlink_msg_odometry_get_child_frame_id(const mavlink_message_t* msg)
  516. {
  517. return _MAV_RETURN_uint8_t(msg, 229);
  518. }
  519. /**
  520. * @brief Get field x from odometry message
  521. *
  522. * @return [m] X Position
  523. */
  524. static inline float mavlink_msg_odometry_get_x(const mavlink_message_t* msg)
  525. {
  526. return _MAV_RETURN_float(msg, 8);
  527. }
  528. /**
  529. * @brief Get field y from odometry message
  530. *
  531. * @return [m] Y Position
  532. */
  533. static inline float mavlink_msg_odometry_get_y(const mavlink_message_t* msg)
  534. {
  535. return _MAV_RETURN_float(msg, 12);
  536. }
  537. /**
  538. * @brief Get field z from odometry message
  539. *
  540. * @return [m] Z Position
  541. */
  542. static inline float mavlink_msg_odometry_get_z(const mavlink_message_t* msg)
  543. {
  544. return _MAV_RETURN_float(msg, 16);
  545. }
  546. /**
  547. * @brief Get field q from odometry message
  548. *
  549. * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
  550. */
  551. static inline uint16_t mavlink_msg_odometry_get_q(const mavlink_message_t* msg, float *q)
  552. {
  553. return _MAV_RETURN_float_array(msg, q, 4, 20);
  554. }
  555. /**
  556. * @brief Get field vx from odometry message
  557. *
  558. * @return [m/s] X linear speed
  559. */
  560. static inline float mavlink_msg_odometry_get_vx(const mavlink_message_t* msg)
  561. {
  562. return _MAV_RETURN_float(msg, 36);
  563. }
  564. /**
  565. * @brief Get field vy from odometry message
  566. *
  567. * @return [m/s] Y linear speed
  568. */
  569. static inline float mavlink_msg_odometry_get_vy(const mavlink_message_t* msg)
  570. {
  571. return _MAV_RETURN_float(msg, 40);
  572. }
  573. /**
  574. * @brief Get field vz from odometry message
  575. *
  576. * @return [m/s] Z linear speed
  577. */
  578. static inline float mavlink_msg_odometry_get_vz(const mavlink_message_t* msg)
  579. {
  580. return _MAV_RETURN_float(msg, 44);
  581. }
  582. /**
  583. * @brief Get field rollspeed from odometry message
  584. *
  585. * @return [rad/s] Roll angular speed
  586. */
  587. static inline float mavlink_msg_odometry_get_rollspeed(const mavlink_message_t* msg)
  588. {
  589. return _MAV_RETURN_float(msg, 48);
  590. }
  591. /**
  592. * @brief Get field pitchspeed from odometry message
  593. *
  594. * @return [rad/s] Pitch angular speed
  595. */
  596. static inline float mavlink_msg_odometry_get_pitchspeed(const mavlink_message_t* msg)
  597. {
  598. return _MAV_RETURN_float(msg, 52);
  599. }
  600. /**
  601. * @brief Get field yawspeed from odometry message
  602. *
  603. * @return [rad/s] Yaw angular speed
  604. */
  605. static inline float mavlink_msg_odometry_get_yawspeed(const mavlink_message_t* msg)
  606. {
  607. return _MAV_RETURN_float(msg, 56);
  608. }
  609. /**
  610. * @brief Get field pose_covariance from odometry message
  611. *
  612. * @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.
  613. */
  614. static inline uint16_t mavlink_msg_odometry_get_pose_covariance(const mavlink_message_t* msg, float *pose_covariance)
  615. {
  616. return _MAV_RETURN_float_array(msg, pose_covariance, 21, 60);
  617. }
  618. /**
  619. * @brief Get field velocity_covariance from odometry message
  620. *
  621. * @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.
  622. */
  623. static inline uint16_t mavlink_msg_odometry_get_velocity_covariance(const mavlink_message_t* msg, float *velocity_covariance)
  624. {
  625. return _MAV_RETURN_float_array(msg, velocity_covariance, 21, 144);
  626. }
  627. /**
  628. * @brief Get field reset_counter from odometry message
  629. *
  630. * @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.
  631. */
  632. static inline uint8_t mavlink_msg_odometry_get_reset_counter(const mavlink_message_t* msg)
  633. {
  634. return _MAV_RETURN_uint8_t(msg, 230);
  635. }
  636. /**
  637. * @brief Get field estimator_type from odometry message
  638. *
  639. * @return Type of estimator that is providing the odometry.
  640. */
  641. static inline uint8_t mavlink_msg_odometry_get_estimator_type(const mavlink_message_t* msg)
  642. {
  643. return _MAV_RETURN_uint8_t(msg, 231);
  644. }
  645. /**
  646. * @brief Get field quality from odometry message
  647. *
  648. * @return [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality
  649. */
  650. static inline int8_t mavlink_msg_odometry_get_quality(const mavlink_message_t* msg)
  651. {
  652. return _MAV_RETURN_int8_t(msg, 232);
  653. }
  654. /**
  655. * @brief Decode a odometry message into a struct
  656. *
  657. * @param msg The message to decode
  658. * @param odometry C-struct to decode the message contents into
  659. */
  660. static inline void mavlink_msg_odometry_decode(const mavlink_message_t* msg, mavlink_odometry_t* odometry)
  661. {
  662. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  663. odometry->time_usec = mavlink_msg_odometry_get_time_usec(msg);
  664. odometry->x = mavlink_msg_odometry_get_x(msg);
  665. odometry->y = mavlink_msg_odometry_get_y(msg);
  666. odometry->z = mavlink_msg_odometry_get_z(msg);
  667. mavlink_msg_odometry_get_q(msg, odometry->q);
  668. odometry->vx = mavlink_msg_odometry_get_vx(msg);
  669. odometry->vy = mavlink_msg_odometry_get_vy(msg);
  670. odometry->vz = mavlink_msg_odometry_get_vz(msg);
  671. odometry->rollspeed = mavlink_msg_odometry_get_rollspeed(msg);
  672. odometry->pitchspeed = mavlink_msg_odometry_get_pitchspeed(msg);
  673. odometry->yawspeed = mavlink_msg_odometry_get_yawspeed(msg);
  674. mavlink_msg_odometry_get_pose_covariance(msg, odometry->pose_covariance);
  675. mavlink_msg_odometry_get_velocity_covariance(msg, odometry->velocity_covariance);
  676. odometry->frame_id = mavlink_msg_odometry_get_frame_id(msg);
  677. odometry->child_frame_id = mavlink_msg_odometry_get_child_frame_id(msg);
  678. odometry->reset_counter = mavlink_msg_odometry_get_reset_counter(msg);
  679. odometry->estimator_type = mavlink_msg_odometry_get_estimator_type(msg);
  680. odometry->quality = mavlink_msg_odometry_get_quality(msg);
  681. #else
  682. uint8_t len = msg->len < MAVLINK_MSG_ID_ODOMETRY_LEN? msg->len : MAVLINK_MSG_ID_ODOMETRY_LEN;
  683. memset(odometry, 0, MAVLINK_MSG_ID_ODOMETRY_LEN);
  684. memcpy(odometry, _MAV_PAYLOAD(msg), len);
  685. #endif
  686. }