mavlink_msg_high_latency.h 36 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788
  1. #pragma once
  2. // MESSAGE HIGH_LATENCY PACKING
  3. #define MAVLINK_MSG_ID_HIGH_LATENCY 234
  4. typedef struct __mavlink_high_latency_t {
  5. uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/
  6. int32_t latitude; /*< [degE7] Latitude*/
  7. int32_t longitude; /*< [degE7] Longitude*/
  8. int16_t roll; /*< [cdeg] roll*/
  9. int16_t pitch; /*< [cdeg] pitch*/
  10. uint16_t heading; /*< [cdeg] heading*/
  11. int16_t heading_sp; /*< [cdeg] heading setpoint*/
  12. int16_t altitude_amsl; /*< [m] Altitude above mean sea level*/
  13. int16_t altitude_sp; /*< [m] Altitude setpoint relative to the home position*/
  14. uint16_t wp_distance; /*< [m] distance to target*/
  15. uint8_t base_mode; /*< Bitmap of enabled system modes.*/
  16. uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/
  17. int8_t throttle; /*< [%] throttle (percentage)*/
  18. uint8_t airspeed; /*< [m/s] airspeed*/
  19. uint8_t airspeed_sp; /*< [m/s] airspeed setpoint*/
  20. uint8_t groundspeed; /*< [m/s] groundspeed*/
  21. int8_t climb_rate; /*< [m/s] climb rate*/
  22. uint8_t gps_nsat; /*< Number of satellites visible. If unknown, set to UINT8_MAX*/
  23. uint8_t gps_fix_type; /*< GPS Fix type.*/
  24. uint8_t battery_remaining; /*< [%] Remaining battery (percentage)*/
  25. int8_t temperature; /*< [degC] Autopilot temperature (degrees C)*/
  26. int8_t temperature_air; /*< [degC] Air temperature (degrees C) from airspeed sensor*/
  27. uint8_t failsafe; /*< failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)*/
  28. uint8_t wp_num; /*< current waypoint number*/
  29. } mavlink_high_latency_t;
  30. #define MAVLINK_MSG_ID_HIGH_LATENCY_LEN 40
  31. #define MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN 40
  32. #define MAVLINK_MSG_ID_234_LEN 40
  33. #define MAVLINK_MSG_ID_234_MIN_LEN 40
  34. #define MAVLINK_MSG_ID_HIGH_LATENCY_CRC 150
  35. #define MAVLINK_MSG_ID_234_CRC 150
  36. #if MAVLINK_COMMAND_24BIT
  37. #define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \
  38. 234, \
  39. "HIGH_LATENCY", \
  40. 24, \
  41. { { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \
  42. { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \
  43. { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \
  44. { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \
  45. { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \
  46. { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \
  47. { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \
  48. { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \
  49. { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \
  50. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \
  51. { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \
  52. { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \
  53. { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \
  54. { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \
  55. { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \
  56. { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \
  57. { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \
  58. { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \
  59. { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \
  60. { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \
  61. { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \
  62. { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \
  63. { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \
  64. { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \
  65. } \
  66. }
  67. #else
  68. #define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \
  69. "HIGH_LATENCY", \
  70. 24, \
  71. { { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \
  72. { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \
  73. { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \
  74. { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \
  75. { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \
  76. { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \
  77. { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \
  78. { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \
  79. { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \
  80. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \
  81. { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \
  82. { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \
  83. { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \
  84. { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \
  85. { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \
  86. { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \
  87. { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \
  88. { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \
  89. { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \
  90. { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \
  91. { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \
  92. { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \
  93. { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \
  94. { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \
  95. } \
  96. }
  97. #endif
  98. /**
  99. * @brief Pack a high_latency message
  100. * @param system_id ID of this system
  101. * @param component_id ID of this component (e.g. 200 for IMU)
  102. * @param msg The MAVLink message to compress the data into
  103. *
  104. * @param base_mode Bitmap of enabled system modes.
  105. * @param custom_mode A bitfield for use for autopilot-specific flags.
  106. * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  107. * @param roll [cdeg] roll
  108. * @param pitch [cdeg] pitch
  109. * @param heading [cdeg] heading
  110. * @param throttle [%] throttle (percentage)
  111. * @param heading_sp [cdeg] heading setpoint
  112. * @param latitude [degE7] Latitude
  113. * @param longitude [degE7] Longitude
  114. * @param altitude_amsl [m] Altitude above mean sea level
  115. * @param altitude_sp [m] Altitude setpoint relative to the home position
  116. * @param airspeed [m/s] airspeed
  117. * @param airspeed_sp [m/s] airspeed setpoint
  118. * @param groundspeed [m/s] groundspeed
  119. * @param climb_rate [m/s] climb rate
  120. * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX
  121. * @param gps_fix_type GPS Fix type.
  122. * @param battery_remaining [%] Remaining battery (percentage)
  123. * @param temperature [degC] Autopilot temperature (degrees C)
  124. * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
  125. * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  126. * @param wp_num current waypoint number
  127. * @param wp_distance [m] distance to target
  128. * @return length of the message in bytes (excluding serial stream start sign)
  129. */
  130. static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  131. uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance)
  132. {
  133. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  134. char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN];
  135. _mav_put_uint32_t(buf, 0, custom_mode);
  136. _mav_put_int32_t(buf, 4, latitude);
  137. _mav_put_int32_t(buf, 8, longitude);
  138. _mav_put_int16_t(buf, 12, roll);
  139. _mav_put_int16_t(buf, 14, pitch);
  140. _mav_put_uint16_t(buf, 16, heading);
  141. _mav_put_int16_t(buf, 18, heading_sp);
  142. _mav_put_int16_t(buf, 20, altitude_amsl);
  143. _mav_put_int16_t(buf, 22, altitude_sp);
  144. _mav_put_uint16_t(buf, 24, wp_distance);
  145. _mav_put_uint8_t(buf, 26, base_mode);
  146. _mav_put_uint8_t(buf, 27, landed_state);
  147. _mav_put_int8_t(buf, 28, throttle);
  148. _mav_put_uint8_t(buf, 29, airspeed);
  149. _mav_put_uint8_t(buf, 30, airspeed_sp);
  150. _mav_put_uint8_t(buf, 31, groundspeed);
  151. _mav_put_int8_t(buf, 32, climb_rate);
  152. _mav_put_uint8_t(buf, 33, gps_nsat);
  153. _mav_put_uint8_t(buf, 34, gps_fix_type);
  154. _mav_put_uint8_t(buf, 35, battery_remaining);
  155. _mav_put_int8_t(buf, 36, temperature);
  156. _mav_put_int8_t(buf, 37, temperature_air);
  157. _mav_put_uint8_t(buf, 38, failsafe);
  158. _mav_put_uint8_t(buf, 39, wp_num);
  159. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  160. #else
  161. mavlink_high_latency_t packet;
  162. packet.custom_mode = custom_mode;
  163. packet.latitude = latitude;
  164. packet.longitude = longitude;
  165. packet.roll = roll;
  166. packet.pitch = pitch;
  167. packet.heading = heading;
  168. packet.heading_sp = heading_sp;
  169. packet.altitude_amsl = altitude_amsl;
  170. packet.altitude_sp = altitude_sp;
  171. packet.wp_distance = wp_distance;
  172. packet.base_mode = base_mode;
  173. packet.landed_state = landed_state;
  174. packet.throttle = throttle;
  175. packet.airspeed = airspeed;
  176. packet.airspeed_sp = airspeed_sp;
  177. packet.groundspeed = groundspeed;
  178. packet.climb_rate = climb_rate;
  179. packet.gps_nsat = gps_nsat;
  180. packet.gps_fix_type = gps_fix_type;
  181. packet.battery_remaining = battery_remaining;
  182. packet.temperature = temperature;
  183. packet.temperature_air = temperature_air;
  184. packet.failsafe = failsafe;
  185. packet.wp_num = wp_num;
  186. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  187. #endif
  188. msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY;
  189. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  190. }
  191. /**
  192. * @brief Pack a high_latency message on a channel
  193. * @param system_id ID of this system
  194. * @param component_id ID of this component (e.g. 200 for IMU)
  195. * @param chan The MAVLink channel this message will be sent over
  196. * @param msg The MAVLink message to compress the data into
  197. * @param base_mode Bitmap of enabled system modes.
  198. * @param custom_mode A bitfield for use for autopilot-specific flags.
  199. * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  200. * @param roll [cdeg] roll
  201. * @param pitch [cdeg] pitch
  202. * @param heading [cdeg] heading
  203. * @param throttle [%] throttle (percentage)
  204. * @param heading_sp [cdeg] heading setpoint
  205. * @param latitude [degE7] Latitude
  206. * @param longitude [degE7] Longitude
  207. * @param altitude_amsl [m] Altitude above mean sea level
  208. * @param altitude_sp [m] Altitude setpoint relative to the home position
  209. * @param airspeed [m/s] airspeed
  210. * @param airspeed_sp [m/s] airspeed setpoint
  211. * @param groundspeed [m/s] groundspeed
  212. * @param climb_rate [m/s] climb rate
  213. * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX
  214. * @param gps_fix_type GPS Fix type.
  215. * @param battery_remaining [%] Remaining battery (percentage)
  216. * @param temperature [degC] Autopilot temperature (degrees C)
  217. * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
  218. * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  219. * @param wp_num current waypoint number
  220. * @param wp_distance [m] distance to target
  221. * @return length of the message in bytes (excluding serial stream start sign)
  222. */
  223. static inline uint16_t mavlink_msg_high_latency_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  224. mavlink_message_t* msg,
  225. uint8_t base_mode,uint32_t custom_mode,uint8_t landed_state,int16_t roll,int16_t pitch,uint16_t heading,int8_t throttle,int16_t heading_sp,int32_t latitude,int32_t longitude,int16_t altitude_amsl,int16_t altitude_sp,uint8_t airspeed,uint8_t airspeed_sp,uint8_t groundspeed,int8_t climb_rate,uint8_t gps_nsat,uint8_t gps_fix_type,uint8_t battery_remaining,int8_t temperature,int8_t temperature_air,uint8_t failsafe,uint8_t wp_num,uint16_t wp_distance)
  226. {
  227. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  228. char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN];
  229. _mav_put_uint32_t(buf, 0, custom_mode);
  230. _mav_put_int32_t(buf, 4, latitude);
  231. _mav_put_int32_t(buf, 8, longitude);
  232. _mav_put_int16_t(buf, 12, roll);
  233. _mav_put_int16_t(buf, 14, pitch);
  234. _mav_put_uint16_t(buf, 16, heading);
  235. _mav_put_int16_t(buf, 18, heading_sp);
  236. _mav_put_int16_t(buf, 20, altitude_amsl);
  237. _mav_put_int16_t(buf, 22, altitude_sp);
  238. _mav_put_uint16_t(buf, 24, wp_distance);
  239. _mav_put_uint8_t(buf, 26, base_mode);
  240. _mav_put_uint8_t(buf, 27, landed_state);
  241. _mav_put_int8_t(buf, 28, throttle);
  242. _mav_put_uint8_t(buf, 29, airspeed);
  243. _mav_put_uint8_t(buf, 30, airspeed_sp);
  244. _mav_put_uint8_t(buf, 31, groundspeed);
  245. _mav_put_int8_t(buf, 32, climb_rate);
  246. _mav_put_uint8_t(buf, 33, gps_nsat);
  247. _mav_put_uint8_t(buf, 34, gps_fix_type);
  248. _mav_put_uint8_t(buf, 35, battery_remaining);
  249. _mav_put_int8_t(buf, 36, temperature);
  250. _mav_put_int8_t(buf, 37, temperature_air);
  251. _mav_put_uint8_t(buf, 38, failsafe);
  252. _mav_put_uint8_t(buf, 39, wp_num);
  253. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  254. #else
  255. mavlink_high_latency_t packet;
  256. packet.custom_mode = custom_mode;
  257. packet.latitude = latitude;
  258. packet.longitude = longitude;
  259. packet.roll = roll;
  260. packet.pitch = pitch;
  261. packet.heading = heading;
  262. packet.heading_sp = heading_sp;
  263. packet.altitude_amsl = altitude_amsl;
  264. packet.altitude_sp = altitude_sp;
  265. packet.wp_distance = wp_distance;
  266. packet.base_mode = base_mode;
  267. packet.landed_state = landed_state;
  268. packet.throttle = throttle;
  269. packet.airspeed = airspeed;
  270. packet.airspeed_sp = airspeed_sp;
  271. packet.groundspeed = groundspeed;
  272. packet.climb_rate = climb_rate;
  273. packet.gps_nsat = gps_nsat;
  274. packet.gps_fix_type = gps_fix_type;
  275. packet.battery_remaining = battery_remaining;
  276. packet.temperature = temperature;
  277. packet.temperature_air = temperature_air;
  278. packet.failsafe = failsafe;
  279. packet.wp_num = wp_num;
  280. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  281. #endif
  282. msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY;
  283. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  284. }
  285. /**
  286. * @brief Encode a high_latency struct
  287. *
  288. * @param system_id ID of this system
  289. * @param component_id ID of this component (e.g. 200 for IMU)
  290. * @param msg The MAVLink message to compress the data into
  291. * @param high_latency C-struct to read the message contents from
  292. */
  293. static inline uint16_t mavlink_msg_high_latency_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency)
  294. {
  295. return mavlink_msg_high_latency_pack(system_id, component_id, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance);
  296. }
  297. /**
  298. * @brief Encode a high_latency struct on a channel
  299. *
  300. * @param system_id ID of this system
  301. * @param component_id ID of this component (e.g. 200 for IMU)
  302. * @param chan The MAVLink channel this message will be sent over
  303. * @param msg The MAVLink message to compress the data into
  304. * @param high_latency C-struct to read the message contents from
  305. */
  306. static inline uint16_t mavlink_msg_high_latency_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency)
  307. {
  308. return mavlink_msg_high_latency_pack_chan(system_id, component_id, chan, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance);
  309. }
  310. /**
  311. * @brief Send a high_latency message
  312. * @param chan MAVLink channel to send the message
  313. *
  314. * @param base_mode Bitmap of enabled system modes.
  315. * @param custom_mode A bitfield for use for autopilot-specific flags.
  316. * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  317. * @param roll [cdeg] roll
  318. * @param pitch [cdeg] pitch
  319. * @param heading [cdeg] heading
  320. * @param throttle [%] throttle (percentage)
  321. * @param heading_sp [cdeg] heading setpoint
  322. * @param latitude [degE7] Latitude
  323. * @param longitude [degE7] Longitude
  324. * @param altitude_amsl [m] Altitude above mean sea level
  325. * @param altitude_sp [m] Altitude setpoint relative to the home position
  326. * @param airspeed [m/s] airspeed
  327. * @param airspeed_sp [m/s] airspeed setpoint
  328. * @param groundspeed [m/s] groundspeed
  329. * @param climb_rate [m/s] climb rate
  330. * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX
  331. * @param gps_fix_type GPS Fix type.
  332. * @param battery_remaining [%] Remaining battery (percentage)
  333. * @param temperature [degC] Autopilot temperature (degrees C)
  334. * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
  335. * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  336. * @param wp_num current waypoint number
  337. * @param wp_distance [m] distance to target
  338. */
  339. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  340. static inline void mavlink_msg_high_latency_send(mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance)
  341. {
  342. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  343. char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN];
  344. _mav_put_uint32_t(buf, 0, custom_mode);
  345. _mav_put_int32_t(buf, 4, latitude);
  346. _mav_put_int32_t(buf, 8, longitude);
  347. _mav_put_int16_t(buf, 12, roll);
  348. _mav_put_int16_t(buf, 14, pitch);
  349. _mav_put_uint16_t(buf, 16, heading);
  350. _mav_put_int16_t(buf, 18, heading_sp);
  351. _mav_put_int16_t(buf, 20, altitude_amsl);
  352. _mav_put_int16_t(buf, 22, altitude_sp);
  353. _mav_put_uint16_t(buf, 24, wp_distance);
  354. _mav_put_uint8_t(buf, 26, base_mode);
  355. _mav_put_uint8_t(buf, 27, landed_state);
  356. _mav_put_int8_t(buf, 28, throttle);
  357. _mav_put_uint8_t(buf, 29, airspeed);
  358. _mav_put_uint8_t(buf, 30, airspeed_sp);
  359. _mav_put_uint8_t(buf, 31, groundspeed);
  360. _mav_put_int8_t(buf, 32, climb_rate);
  361. _mav_put_uint8_t(buf, 33, gps_nsat);
  362. _mav_put_uint8_t(buf, 34, gps_fix_type);
  363. _mav_put_uint8_t(buf, 35, battery_remaining);
  364. _mav_put_int8_t(buf, 36, temperature);
  365. _mav_put_int8_t(buf, 37, temperature_air);
  366. _mav_put_uint8_t(buf, 38, failsafe);
  367. _mav_put_uint8_t(buf, 39, wp_num);
  368. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  369. #else
  370. mavlink_high_latency_t packet;
  371. packet.custom_mode = custom_mode;
  372. packet.latitude = latitude;
  373. packet.longitude = longitude;
  374. packet.roll = roll;
  375. packet.pitch = pitch;
  376. packet.heading = heading;
  377. packet.heading_sp = heading_sp;
  378. packet.altitude_amsl = altitude_amsl;
  379. packet.altitude_sp = altitude_sp;
  380. packet.wp_distance = wp_distance;
  381. packet.base_mode = base_mode;
  382. packet.landed_state = landed_state;
  383. packet.throttle = throttle;
  384. packet.airspeed = airspeed;
  385. packet.airspeed_sp = airspeed_sp;
  386. packet.groundspeed = groundspeed;
  387. packet.climb_rate = climb_rate;
  388. packet.gps_nsat = gps_nsat;
  389. packet.gps_fix_type = gps_fix_type;
  390. packet.battery_remaining = battery_remaining;
  391. packet.temperature = temperature;
  392. packet.temperature_air = temperature_air;
  393. packet.failsafe = failsafe;
  394. packet.wp_num = wp_num;
  395. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)&packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  396. #endif
  397. }
  398. /**
  399. * @brief Send a high_latency message
  400. * @param chan MAVLink channel to send the message
  401. * @param struct The MAVLink struct to serialize
  402. */
  403. static inline void mavlink_msg_high_latency_send_struct(mavlink_channel_t chan, const mavlink_high_latency_t* high_latency)
  404. {
  405. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  406. mavlink_msg_high_latency_send(chan, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance);
  407. #else
  408. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)high_latency, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  409. #endif
  410. }
  411. #if MAVLINK_MSG_ID_HIGH_LATENCY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  412. /*
  413. This variant of _send() can be used to save stack space by re-using
  414. memory from the receive buffer. The caller provides a
  415. mavlink_message_t which is the size of a full mavlink message. This
  416. is usually the receive buffer for the channel, and allows a reply to an
  417. incoming message with minimum stack space usage.
  418. */
  419. static inline void mavlink_msg_high_latency_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance)
  420. {
  421. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  422. char *buf = (char *)msgbuf;
  423. _mav_put_uint32_t(buf, 0, custom_mode);
  424. _mav_put_int32_t(buf, 4, latitude);
  425. _mav_put_int32_t(buf, 8, longitude);
  426. _mav_put_int16_t(buf, 12, roll);
  427. _mav_put_int16_t(buf, 14, pitch);
  428. _mav_put_uint16_t(buf, 16, heading);
  429. _mav_put_int16_t(buf, 18, heading_sp);
  430. _mav_put_int16_t(buf, 20, altitude_amsl);
  431. _mav_put_int16_t(buf, 22, altitude_sp);
  432. _mav_put_uint16_t(buf, 24, wp_distance);
  433. _mav_put_uint8_t(buf, 26, base_mode);
  434. _mav_put_uint8_t(buf, 27, landed_state);
  435. _mav_put_int8_t(buf, 28, throttle);
  436. _mav_put_uint8_t(buf, 29, airspeed);
  437. _mav_put_uint8_t(buf, 30, airspeed_sp);
  438. _mav_put_uint8_t(buf, 31, groundspeed);
  439. _mav_put_int8_t(buf, 32, climb_rate);
  440. _mav_put_uint8_t(buf, 33, gps_nsat);
  441. _mav_put_uint8_t(buf, 34, gps_fix_type);
  442. _mav_put_uint8_t(buf, 35, battery_remaining);
  443. _mav_put_int8_t(buf, 36, temperature);
  444. _mav_put_int8_t(buf, 37, temperature_air);
  445. _mav_put_uint8_t(buf, 38, failsafe);
  446. _mav_put_uint8_t(buf, 39, wp_num);
  447. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  448. #else
  449. mavlink_high_latency_t *packet = (mavlink_high_latency_t *)msgbuf;
  450. packet->custom_mode = custom_mode;
  451. packet->latitude = latitude;
  452. packet->longitude = longitude;
  453. packet->roll = roll;
  454. packet->pitch = pitch;
  455. packet->heading = heading;
  456. packet->heading_sp = heading_sp;
  457. packet->altitude_amsl = altitude_amsl;
  458. packet->altitude_sp = altitude_sp;
  459. packet->wp_distance = wp_distance;
  460. packet->base_mode = base_mode;
  461. packet->landed_state = landed_state;
  462. packet->throttle = throttle;
  463. packet->airspeed = airspeed;
  464. packet->airspeed_sp = airspeed_sp;
  465. packet->groundspeed = groundspeed;
  466. packet->climb_rate = climb_rate;
  467. packet->gps_nsat = gps_nsat;
  468. packet->gps_fix_type = gps_fix_type;
  469. packet->battery_remaining = battery_remaining;
  470. packet->temperature = temperature;
  471. packet->temperature_air = temperature_air;
  472. packet->failsafe = failsafe;
  473. packet->wp_num = wp_num;
  474. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  475. #endif
  476. }
  477. #endif
  478. #endif
  479. // MESSAGE HIGH_LATENCY UNPACKING
  480. /**
  481. * @brief Get field base_mode from high_latency message
  482. *
  483. * @return Bitmap of enabled system modes.
  484. */
  485. static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_message_t* msg)
  486. {
  487. return _MAV_RETURN_uint8_t(msg, 26);
  488. }
  489. /**
  490. * @brief Get field custom_mode from high_latency message
  491. *
  492. * @return A bitfield for use for autopilot-specific flags.
  493. */
  494. static inline uint32_t mavlink_msg_high_latency_get_custom_mode(const mavlink_message_t* msg)
  495. {
  496. return _MAV_RETURN_uint32_t(msg, 0);
  497. }
  498. /**
  499. * @brief Get field landed_state from high_latency message
  500. *
  501. * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  502. */
  503. static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_message_t* msg)
  504. {
  505. return _MAV_RETURN_uint8_t(msg, 27);
  506. }
  507. /**
  508. * @brief Get field roll from high_latency message
  509. *
  510. * @return [cdeg] roll
  511. */
  512. static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* msg)
  513. {
  514. return _MAV_RETURN_int16_t(msg, 12);
  515. }
  516. /**
  517. * @brief Get field pitch from high_latency message
  518. *
  519. * @return [cdeg] pitch
  520. */
  521. static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t* msg)
  522. {
  523. return _MAV_RETURN_int16_t(msg, 14);
  524. }
  525. /**
  526. * @brief Get field heading from high_latency message
  527. *
  528. * @return [cdeg] heading
  529. */
  530. static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_message_t* msg)
  531. {
  532. return _MAV_RETURN_uint16_t(msg, 16);
  533. }
  534. /**
  535. * @brief Get field throttle from high_latency message
  536. *
  537. * @return [%] throttle (percentage)
  538. */
  539. static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message_t* msg)
  540. {
  541. return _MAV_RETURN_int8_t(msg, 28);
  542. }
  543. /**
  544. * @brief Get field heading_sp from high_latency message
  545. *
  546. * @return [cdeg] heading setpoint
  547. */
  548. static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_message_t* msg)
  549. {
  550. return _MAV_RETURN_int16_t(msg, 18);
  551. }
  552. /**
  553. * @brief Get field latitude from high_latency message
  554. *
  555. * @return [degE7] Latitude
  556. */
  557. static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_message_t* msg)
  558. {
  559. return _MAV_RETURN_int32_t(msg, 4);
  560. }
  561. /**
  562. * @brief Get field longitude from high_latency message
  563. *
  564. * @return [degE7] Longitude
  565. */
  566. static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_message_t* msg)
  567. {
  568. return _MAV_RETURN_int32_t(msg, 8);
  569. }
  570. /**
  571. * @brief Get field altitude_amsl from high_latency message
  572. *
  573. * @return [m] Altitude above mean sea level
  574. */
  575. static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_message_t* msg)
  576. {
  577. return _MAV_RETURN_int16_t(msg, 20);
  578. }
  579. /**
  580. * @brief Get field altitude_sp from high_latency message
  581. *
  582. * @return [m] Altitude setpoint relative to the home position
  583. */
  584. static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_message_t* msg)
  585. {
  586. return _MAV_RETURN_int16_t(msg, 22);
  587. }
  588. /**
  589. * @brief Get field airspeed from high_latency message
  590. *
  591. * @return [m/s] airspeed
  592. */
  593. static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_message_t* msg)
  594. {
  595. return _MAV_RETURN_uint8_t(msg, 29);
  596. }
  597. /**
  598. * @brief Get field airspeed_sp from high_latency message
  599. *
  600. * @return [m/s] airspeed setpoint
  601. */
  602. static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_message_t* msg)
  603. {
  604. return _MAV_RETURN_uint8_t(msg, 30);
  605. }
  606. /**
  607. * @brief Get field groundspeed from high_latency message
  608. *
  609. * @return [m/s] groundspeed
  610. */
  611. static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_message_t* msg)
  612. {
  613. return _MAV_RETURN_uint8_t(msg, 31);
  614. }
  615. /**
  616. * @brief Get field climb_rate from high_latency message
  617. *
  618. * @return [m/s] climb rate
  619. */
  620. static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_message_t* msg)
  621. {
  622. return _MAV_RETURN_int8_t(msg, 32);
  623. }
  624. /**
  625. * @brief Get field gps_nsat from high_latency message
  626. *
  627. * @return Number of satellites visible. If unknown, set to UINT8_MAX
  628. */
  629. static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_message_t* msg)
  630. {
  631. return _MAV_RETURN_uint8_t(msg, 33);
  632. }
  633. /**
  634. * @brief Get field gps_fix_type from high_latency message
  635. *
  636. * @return GPS Fix type.
  637. */
  638. static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_message_t* msg)
  639. {
  640. return _MAV_RETURN_uint8_t(msg, 34);
  641. }
  642. /**
  643. * @brief Get field battery_remaining from high_latency message
  644. *
  645. * @return [%] Remaining battery (percentage)
  646. */
  647. static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavlink_message_t* msg)
  648. {
  649. return _MAV_RETURN_uint8_t(msg, 35);
  650. }
  651. /**
  652. * @brief Get field temperature from high_latency message
  653. *
  654. * @return [degC] Autopilot temperature (degrees C)
  655. */
  656. static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_message_t* msg)
  657. {
  658. return _MAV_RETURN_int8_t(msg, 36);
  659. }
  660. /**
  661. * @brief Get field temperature_air from high_latency message
  662. *
  663. * @return [degC] Air temperature (degrees C) from airspeed sensor
  664. */
  665. static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_message_t* msg)
  666. {
  667. return _MAV_RETURN_int8_t(msg, 37);
  668. }
  669. /**
  670. * @brief Get field failsafe from high_latency message
  671. *
  672. * @return failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  673. */
  674. static inline uint8_t mavlink_msg_high_latency_get_failsafe(const mavlink_message_t* msg)
  675. {
  676. return _MAV_RETURN_uint8_t(msg, 38);
  677. }
  678. /**
  679. * @brief Get field wp_num from high_latency message
  680. *
  681. * @return current waypoint number
  682. */
  683. static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_t* msg)
  684. {
  685. return _MAV_RETURN_uint8_t(msg, 39);
  686. }
  687. /**
  688. * @brief Get field wp_distance from high_latency message
  689. *
  690. * @return [m] distance to target
  691. */
  692. static inline uint16_t mavlink_msg_high_latency_get_wp_distance(const mavlink_message_t* msg)
  693. {
  694. return _MAV_RETURN_uint16_t(msg, 24);
  695. }
  696. /**
  697. * @brief Decode a high_latency message into a struct
  698. *
  699. * @param msg The message to decode
  700. * @param high_latency C-struct to decode the message contents into
  701. */
  702. static inline void mavlink_msg_high_latency_decode(const mavlink_message_t* msg, mavlink_high_latency_t* high_latency)
  703. {
  704. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  705. high_latency->custom_mode = mavlink_msg_high_latency_get_custom_mode(msg);
  706. high_latency->latitude = mavlink_msg_high_latency_get_latitude(msg);
  707. high_latency->longitude = mavlink_msg_high_latency_get_longitude(msg);
  708. high_latency->roll = mavlink_msg_high_latency_get_roll(msg);
  709. high_latency->pitch = mavlink_msg_high_latency_get_pitch(msg);
  710. high_latency->heading = mavlink_msg_high_latency_get_heading(msg);
  711. high_latency->heading_sp = mavlink_msg_high_latency_get_heading_sp(msg);
  712. high_latency->altitude_amsl = mavlink_msg_high_latency_get_altitude_amsl(msg);
  713. high_latency->altitude_sp = mavlink_msg_high_latency_get_altitude_sp(msg);
  714. high_latency->wp_distance = mavlink_msg_high_latency_get_wp_distance(msg);
  715. high_latency->base_mode = mavlink_msg_high_latency_get_base_mode(msg);
  716. high_latency->landed_state = mavlink_msg_high_latency_get_landed_state(msg);
  717. high_latency->throttle = mavlink_msg_high_latency_get_throttle(msg);
  718. high_latency->airspeed = mavlink_msg_high_latency_get_airspeed(msg);
  719. high_latency->airspeed_sp = mavlink_msg_high_latency_get_airspeed_sp(msg);
  720. high_latency->groundspeed = mavlink_msg_high_latency_get_groundspeed(msg);
  721. high_latency->climb_rate = mavlink_msg_high_latency_get_climb_rate(msg);
  722. high_latency->gps_nsat = mavlink_msg_high_latency_get_gps_nsat(msg);
  723. high_latency->gps_fix_type = mavlink_msg_high_latency_get_gps_fix_type(msg);
  724. high_latency->battery_remaining = mavlink_msg_high_latency_get_battery_remaining(msg);
  725. high_latency->temperature = mavlink_msg_high_latency_get_temperature(msg);
  726. high_latency->temperature_air = mavlink_msg_high_latency_get_temperature_air(msg);
  727. high_latency->failsafe = mavlink_msg_high_latency_get_failsafe(msg);
  728. high_latency->wp_num = mavlink_msg_high_latency_get_wp_num(msg);
  729. #else
  730. uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY_LEN;
  731. memset(high_latency, 0, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  732. memcpy(high_latency, _MAV_PAYLOAD(msg), len);
  733. #endif
  734. }