mavlink_msg_high_latency.h 42 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904
  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
  193. * @param system_id ID of this system
  194. * @param component_id ID of this component (e.g. 200 for IMU)
  195. * @param status MAVLink status structure
  196. * @param msg The MAVLink message to compress the data into
  197. *
  198. * @param base_mode Bitmap of enabled system modes.
  199. * @param custom_mode A bitfield for use for autopilot-specific flags.
  200. * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  201. * @param roll [cdeg] roll
  202. * @param pitch [cdeg] pitch
  203. * @param heading [cdeg] heading
  204. * @param throttle [%] throttle (percentage)
  205. * @param heading_sp [cdeg] heading setpoint
  206. * @param latitude [degE7] Latitude
  207. * @param longitude [degE7] Longitude
  208. * @param altitude_amsl [m] Altitude above mean sea level
  209. * @param altitude_sp [m] Altitude setpoint relative to the home position
  210. * @param airspeed [m/s] airspeed
  211. * @param airspeed_sp [m/s] airspeed setpoint
  212. * @param groundspeed [m/s] groundspeed
  213. * @param climb_rate [m/s] climb rate
  214. * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX
  215. * @param gps_fix_type GPS Fix type.
  216. * @param battery_remaining [%] Remaining battery (percentage)
  217. * @param temperature [degC] Autopilot temperature (degrees C)
  218. * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
  219. * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  220. * @param wp_num current waypoint number
  221. * @param wp_distance [m] distance to target
  222. * @return length of the message in bytes (excluding serial stream start sign)
  223. */
  224. static inline uint16_t mavlink_msg_high_latency_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  284. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC);
  285. #else
  286. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  287. #endif
  288. }
  289. /**
  290. * @brief Pack a high_latency message on a channel
  291. * @param system_id ID of this system
  292. * @param component_id ID of this component (e.g. 200 for IMU)
  293. * @param chan The MAVLink channel this message will be sent over
  294. * @param msg The MAVLink message to compress the data into
  295. * @param base_mode Bitmap of enabled system modes.
  296. * @param custom_mode A bitfield for use for autopilot-specific flags.
  297. * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  298. * @param roll [cdeg] roll
  299. * @param pitch [cdeg] pitch
  300. * @param heading [cdeg] heading
  301. * @param throttle [%] throttle (percentage)
  302. * @param heading_sp [cdeg] heading setpoint
  303. * @param latitude [degE7] Latitude
  304. * @param longitude [degE7] Longitude
  305. * @param altitude_amsl [m] Altitude above mean sea level
  306. * @param altitude_sp [m] Altitude setpoint relative to the home position
  307. * @param airspeed [m/s] airspeed
  308. * @param airspeed_sp [m/s] airspeed setpoint
  309. * @param groundspeed [m/s] groundspeed
  310. * @param climb_rate [m/s] climb rate
  311. * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX
  312. * @param gps_fix_type GPS Fix type.
  313. * @param battery_remaining [%] Remaining battery (percentage)
  314. * @param temperature [degC] Autopilot temperature (degrees C)
  315. * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
  316. * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  317. * @param wp_num current waypoint number
  318. * @param wp_distance [m] distance to target
  319. * @return length of the message in bytes (excluding serial stream start sign)
  320. */
  321. static inline uint16_t mavlink_msg_high_latency_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  322. mavlink_message_t* msg,
  323. 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)
  324. {
  325. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  326. char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN];
  327. _mav_put_uint32_t(buf, 0, custom_mode);
  328. _mav_put_int32_t(buf, 4, latitude);
  329. _mav_put_int32_t(buf, 8, longitude);
  330. _mav_put_int16_t(buf, 12, roll);
  331. _mav_put_int16_t(buf, 14, pitch);
  332. _mav_put_uint16_t(buf, 16, heading);
  333. _mav_put_int16_t(buf, 18, heading_sp);
  334. _mav_put_int16_t(buf, 20, altitude_amsl);
  335. _mav_put_int16_t(buf, 22, altitude_sp);
  336. _mav_put_uint16_t(buf, 24, wp_distance);
  337. _mav_put_uint8_t(buf, 26, base_mode);
  338. _mav_put_uint8_t(buf, 27, landed_state);
  339. _mav_put_int8_t(buf, 28, throttle);
  340. _mav_put_uint8_t(buf, 29, airspeed);
  341. _mav_put_uint8_t(buf, 30, airspeed_sp);
  342. _mav_put_uint8_t(buf, 31, groundspeed);
  343. _mav_put_int8_t(buf, 32, climb_rate);
  344. _mav_put_uint8_t(buf, 33, gps_nsat);
  345. _mav_put_uint8_t(buf, 34, gps_fix_type);
  346. _mav_put_uint8_t(buf, 35, battery_remaining);
  347. _mav_put_int8_t(buf, 36, temperature);
  348. _mav_put_int8_t(buf, 37, temperature_air);
  349. _mav_put_uint8_t(buf, 38, failsafe);
  350. _mav_put_uint8_t(buf, 39, wp_num);
  351. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  352. #else
  353. mavlink_high_latency_t packet;
  354. packet.custom_mode = custom_mode;
  355. packet.latitude = latitude;
  356. packet.longitude = longitude;
  357. packet.roll = roll;
  358. packet.pitch = pitch;
  359. packet.heading = heading;
  360. packet.heading_sp = heading_sp;
  361. packet.altitude_amsl = altitude_amsl;
  362. packet.altitude_sp = altitude_sp;
  363. packet.wp_distance = wp_distance;
  364. packet.base_mode = base_mode;
  365. packet.landed_state = landed_state;
  366. packet.throttle = throttle;
  367. packet.airspeed = airspeed;
  368. packet.airspeed_sp = airspeed_sp;
  369. packet.groundspeed = groundspeed;
  370. packet.climb_rate = climb_rate;
  371. packet.gps_nsat = gps_nsat;
  372. packet.gps_fix_type = gps_fix_type;
  373. packet.battery_remaining = battery_remaining;
  374. packet.temperature = temperature;
  375. packet.temperature_air = temperature_air;
  376. packet.failsafe = failsafe;
  377. packet.wp_num = wp_num;
  378. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  379. #endif
  380. msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY;
  381. 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);
  382. }
  383. /**
  384. * @brief Encode a high_latency struct
  385. *
  386. * @param system_id ID of this system
  387. * @param component_id ID of this component (e.g. 200 for IMU)
  388. * @param msg The MAVLink message to compress the data into
  389. * @param high_latency C-struct to read the message contents from
  390. */
  391. 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)
  392. {
  393. 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);
  394. }
  395. /**
  396. * @brief Encode a high_latency struct on a channel
  397. *
  398. * @param system_id ID of this system
  399. * @param component_id ID of this component (e.g. 200 for IMU)
  400. * @param chan The MAVLink channel this message will be sent over
  401. * @param msg The MAVLink message to compress the data into
  402. * @param high_latency C-struct to read the message contents from
  403. */
  404. 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)
  405. {
  406. 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);
  407. }
  408. /**
  409. * @brief Encode a high_latency struct with provided status structure
  410. *
  411. * @param system_id ID of this system
  412. * @param component_id ID of this component (e.g. 200 for IMU)
  413. * @param status MAVLink status structure
  414. * @param msg The MAVLink message to compress the data into
  415. * @param high_latency C-struct to read the message contents from
  416. */
  417. static inline uint16_t mavlink_msg_high_latency_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency)
  418. {
  419. return mavlink_msg_high_latency_pack_status(system_id, component_id, _status, 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);
  420. }
  421. /**
  422. * @brief Send a high_latency message
  423. * @param chan MAVLink channel to send the message
  424. *
  425. * @param base_mode Bitmap of enabled system modes.
  426. * @param custom_mode A bitfield for use for autopilot-specific flags.
  427. * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  428. * @param roll [cdeg] roll
  429. * @param pitch [cdeg] pitch
  430. * @param heading [cdeg] heading
  431. * @param throttle [%] throttle (percentage)
  432. * @param heading_sp [cdeg] heading setpoint
  433. * @param latitude [degE7] Latitude
  434. * @param longitude [degE7] Longitude
  435. * @param altitude_amsl [m] Altitude above mean sea level
  436. * @param altitude_sp [m] Altitude setpoint relative to the home position
  437. * @param airspeed [m/s] airspeed
  438. * @param airspeed_sp [m/s] airspeed setpoint
  439. * @param groundspeed [m/s] groundspeed
  440. * @param climb_rate [m/s] climb rate
  441. * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX
  442. * @param gps_fix_type GPS Fix type.
  443. * @param battery_remaining [%] Remaining battery (percentage)
  444. * @param temperature [degC] Autopilot temperature (degrees C)
  445. * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor
  446. * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  447. * @param wp_num current waypoint number
  448. * @param wp_distance [m] distance to target
  449. */
  450. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  451. 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)
  452. {
  453. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  454. char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN];
  455. _mav_put_uint32_t(buf, 0, custom_mode);
  456. _mav_put_int32_t(buf, 4, latitude);
  457. _mav_put_int32_t(buf, 8, longitude);
  458. _mav_put_int16_t(buf, 12, roll);
  459. _mav_put_int16_t(buf, 14, pitch);
  460. _mav_put_uint16_t(buf, 16, heading);
  461. _mav_put_int16_t(buf, 18, heading_sp);
  462. _mav_put_int16_t(buf, 20, altitude_amsl);
  463. _mav_put_int16_t(buf, 22, altitude_sp);
  464. _mav_put_uint16_t(buf, 24, wp_distance);
  465. _mav_put_uint8_t(buf, 26, base_mode);
  466. _mav_put_uint8_t(buf, 27, landed_state);
  467. _mav_put_int8_t(buf, 28, throttle);
  468. _mav_put_uint8_t(buf, 29, airspeed);
  469. _mav_put_uint8_t(buf, 30, airspeed_sp);
  470. _mav_put_uint8_t(buf, 31, groundspeed);
  471. _mav_put_int8_t(buf, 32, climb_rate);
  472. _mav_put_uint8_t(buf, 33, gps_nsat);
  473. _mav_put_uint8_t(buf, 34, gps_fix_type);
  474. _mav_put_uint8_t(buf, 35, battery_remaining);
  475. _mav_put_int8_t(buf, 36, temperature);
  476. _mav_put_int8_t(buf, 37, temperature_air);
  477. _mav_put_uint8_t(buf, 38, failsafe);
  478. _mav_put_uint8_t(buf, 39, wp_num);
  479. _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);
  480. #else
  481. mavlink_high_latency_t packet;
  482. packet.custom_mode = custom_mode;
  483. packet.latitude = latitude;
  484. packet.longitude = longitude;
  485. packet.roll = roll;
  486. packet.pitch = pitch;
  487. packet.heading = heading;
  488. packet.heading_sp = heading_sp;
  489. packet.altitude_amsl = altitude_amsl;
  490. packet.altitude_sp = altitude_sp;
  491. packet.wp_distance = wp_distance;
  492. packet.base_mode = base_mode;
  493. packet.landed_state = landed_state;
  494. packet.throttle = throttle;
  495. packet.airspeed = airspeed;
  496. packet.airspeed_sp = airspeed_sp;
  497. packet.groundspeed = groundspeed;
  498. packet.climb_rate = climb_rate;
  499. packet.gps_nsat = gps_nsat;
  500. packet.gps_fix_type = gps_fix_type;
  501. packet.battery_remaining = battery_remaining;
  502. packet.temperature = temperature;
  503. packet.temperature_air = temperature_air;
  504. packet.failsafe = failsafe;
  505. packet.wp_num = wp_num;
  506. _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);
  507. #endif
  508. }
  509. /**
  510. * @brief Send a high_latency message
  511. * @param chan MAVLink channel to send the message
  512. * @param struct The MAVLink struct to serialize
  513. */
  514. static inline void mavlink_msg_high_latency_send_struct(mavlink_channel_t chan, const mavlink_high_latency_t* high_latency)
  515. {
  516. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  517. 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);
  518. #else
  519. _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);
  520. #endif
  521. }
  522. #if MAVLINK_MSG_ID_HIGH_LATENCY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  523. /*
  524. This variant of _send() can be used to save stack space by re-using
  525. memory from the receive buffer. The caller provides a
  526. mavlink_message_t which is the size of a full mavlink message. This
  527. is usually the receive buffer for the channel, and allows a reply to an
  528. incoming message with minimum stack space usage.
  529. */
  530. 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)
  531. {
  532. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  533. char *buf = (char *)msgbuf;
  534. _mav_put_uint32_t(buf, 0, custom_mode);
  535. _mav_put_int32_t(buf, 4, latitude);
  536. _mav_put_int32_t(buf, 8, longitude);
  537. _mav_put_int16_t(buf, 12, roll);
  538. _mav_put_int16_t(buf, 14, pitch);
  539. _mav_put_uint16_t(buf, 16, heading);
  540. _mav_put_int16_t(buf, 18, heading_sp);
  541. _mav_put_int16_t(buf, 20, altitude_amsl);
  542. _mav_put_int16_t(buf, 22, altitude_sp);
  543. _mav_put_uint16_t(buf, 24, wp_distance);
  544. _mav_put_uint8_t(buf, 26, base_mode);
  545. _mav_put_uint8_t(buf, 27, landed_state);
  546. _mav_put_int8_t(buf, 28, throttle);
  547. _mav_put_uint8_t(buf, 29, airspeed);
  548. _mav_put_uint8_t(buf, 30, airspeed_sp);
  549. _mav_put_uint8_t(buf, 31, groundspeed);
  550. _mav_put_int8_t(buf, 32, climb_rate);
  551. _mav_put_uint8_t(buf, 33, gps_nsat);
  552. _mav_put_uint8_t(buf, 34, gps_fix_type);
  553. _mav_put_uint8_t(buf, 35, battery_remaining);
  554. _mav_put_int8_t(buf, 36, temperature);
  555. _mav_put_int8_t(buf, 37, temperature_air);
  556. _mav_put_uint8_t(buf, 38, failsafe);
  557. _mav_put_uint8_t(buf, 39, wp_num);
  558. _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);
  559. #else
  560. mavlink_high_latency_t *packet = (mavlink_high_latency_t *)msgbuf;
  561. packet->custom_mode = custom_mode;
  562. packet->latitude = latitude;
  563. packet->longitude = longitude;
  564. packet->roll = roll;
  565. packet->pitch = pitch;
  566. packet->heading = heading;
  567. packet->heading_sp = heading_sp;
  568. packet->altitude_amsl = altitude_amsl;
  569. packet->altitude_sp = altitude_sp;
  570. packet->wp_distance = wp_distance;
  571. packet->base_mode = base_mode;
  572. packet->landed_state = landed_state;
  573. packet->throttle = throttle;
  574. packet->airspeed = airspeed;
  575. packet->airspeed_sp = airspeed_sp;
  576. packet->groundspeed = groundspeed;
  577. packet->climb_rate = climb_rate;
  578. packet->gps_nsat = gps_nsat;
  579. packet->gps_fix_type = gps_fix_type;
  580. packet->battery_remaining = battery_remaining;
  581. packet->temperature = temperature;
  582. packet->temperature_air = temperature_air;
  583. packet->failsafe = failsafe;
  584. packet->wp_num = wp_num;
  585. _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);
  586. #endif
  587. }
  588. #endif
  589. #endif
  590. // MESSAGE HIGH_LATENCY UNPACKING
  591. /**
  592. * @brief Get field base_mode from high_latency message
  593. *
  594. * @return Bitmap of enabled system modes.
  595. */
  596. static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_message_t* msg)
  597. {
  598. return _MAV_RETURN_uint8_t(msg, 26);
  599. }
  600. /**
  601. * @brief Get field custom_mode from high_latency message
  602. *
  603. * @return A bitfield for use for autopilot-specific flags.
  604. */
  605. static inline uint32_t mavlink_msg_high_latency_get_custom_mode(const mavlink_message_t* msg)
  606. {
  607. return _MAV_RETURN_uint32_t(msg, 0);
  608. }
  609. /**
  610. * @brief Get field landed_state from high_latency message
  611. *
  612. * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
  613. */
  614. static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_message_t* msg)
  615. {
  616. return _MAV_RETURN_uint8_t(msg, 27);
  617. }
  618. /**
  619. * @brief Get field roll from high_latency message
  620. *
  621. * @return [cdeg] roll
  622. */
  623. static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* msg)
  624. {
  625. return _MAV_RETURN_int16_t(msg, 12);
  626. }
  627. /**
  628. * @brief Get field pitch from high_latency message
  629. *
  630. * @return [cdeg] pitch
  631. */
  632. static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t* msg)
  633. {
  634. return _MAV_RETURN_int16_t(msg, 14);
  635. }
  636. /**
  637. * @brief Get field heading from high_latency message
  638. *
  639. * @return [cdeg] heading
  640. */
  641. static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_message_t* msg)
  642. {
  643. return _MAV_RETURN_uint16_t(msg, 16);
  644. }
  645. /**
  646. * @brief Get field throttle from high_latency message
  647. *
  648. * @return [%] throttle (percentage)
  649. */
  650. static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message_t* msg)
  651. {
  652. return _MAV_RETURN_int8_t(msg, 28);
  653. }
  654. /**
  655. * @brief Get field heading_sp from high_latency message
  656. *
  657. * @return [cdeg] heading setpoint
  658. */
  659. static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_message_t* msg)
  660. {
  661. return _MAV_RETURN_int16_t(msg, 18);
  662. }
  663. /**
  664. * @brief Get field latitude from high_latency message
  665. *
  666. * @return [degE7] Latitude
  667. */
  668. static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_message_t* msg)
  669. {
  670. return _MAV_RETURN_int32_t(msg, 4);
  671. }
  672. /**
  673. * @brief Get field longitude from high_latency message
  674. *
  675. * @return [degE7] Longitude
  676. */
  677. static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_message_t* msg)
  678. {
  679. return _MAV_RETURN_int32_t(msg, 8);
  680. }
  681. /**
  682. * @brief Get field altitude_amsl from high_latency message
  683. *
  684. * @return [m] Altitude above mean sea level
  685. */
  686. static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_message_t* msg)
  687. {
  688. return _MAV_RETURN_int16_t(msg, 20);
  689. }
  690. /**
  691. * @brief Get field altitude_sp from high_latency message
  692. *
  693. * @return [m] Altitude setpoint relative to the home position
  694. */
  695. static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_message_t* msg)
  696. {
  697. return _MAV_RETURN_int16_t(msg, 22);
  698. }
  699. /**
  700. * @brief Get field airspeed from high_latency message
  701. *
  702. * @return [m/s] airspeed
  703. */
  704. static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_message_t* msg)
  705. {
  706. return _MAV_RETURN_uint8_t(msg, 29);
  707. }
  708. /**
  709. * @brief Get field airspeed_sp from high_latency message
  710. *
  711. * @return [m/s] airspeed setpoint
  712. */
  713. static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_message_t* msg)
  714. {
  715. return _MAV_RETURN_uint8_t(msg, 30);
  716. }
  717. /**
  718. * @brief Get field groundspeed from high_latency message
  719. *
  720. * @return [m/s] groundspeed
  721. */
  722. static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_message_t* msg)
  723. {
  724. return _MAV_RETURN_uint8_t(msg, 31);
  725. }
  726. /**
  727. * @brief Get field climb_rate from high_latency message
  728. *
  729. * @return [m/s] climb rate
  730. */
  731. static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_message_t* msg)
  732. {
  733. return _MAV_RETURN_int8_t(msg, 32);
  734. }
  735. /**
  736. * @brief Get field gps_nsat from high_latency message
  737. *
  738. * @return Number of satellites visible. If unknown, set to UINT8_MAX
  739. */
  740. static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_message_t* msg)
  741. {
  742. return _MAV_RETURN_uint8_t(msg, 33);
  743. }
  744. /**
  745. * @brief Get field gps_fix_type from high_latency message
  746. *
  747. * @return GPS Fix type.
  748. */
  749. static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_message_t* msg)
  750. {
  751. return _MAV_RETURN_uint8_t(msg, 34);
  752. }
  753. /**
  754. * @brief Get field battery_remaining from high_latency message
  755. *
  756. * @return [%] Remaining battery (percentage)
  757. */
  758. static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavlink_message_t* msg)
  759. {
  760. return _MAV_RETURN_uint8_t(msg, 35);
  761. }
  762. /**
  763. * @brief Get field temperature from high_latency message
  764. *
  765. * @return [degC] Autopilot temperature (degrees C)
  766. */
  767. static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_message_t* msg)
  768. {
  769. return _MAV_RETURN_int8_t(msg, 36);
  770. }
  771. /**
  772. * @brief Get field temperature_air from high_latency message
  773. *
  774. * @return [degC] Air temperature (degrees C) from airspeed sensor
  775. */
  776. static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_message_t* msg)
  777. {
  778. return _MAV_RETURN_int8_t(msg, 37);
  779. }
  780. /**
  781. * @brief Get field failsafe from high_latency message
  782. *
  783. * @return failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
  784. */
  785. static inline uint8_t mavlink_msg_high_latency_get_failsafe(const mavlink_message_t* msg)
  786. {
  787. return _MAV_RETURN_uint8_t(msg, 38);
  788. }
  789. /**
  790. * @brief Get field wp_num from high_latency message
  791. *
  792. * @return current waypoint number
  793. */
  794. static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_t* msg)
  795. {
  796. return _MAV_RETURN_uint8_t(msg, 39);
  797. }
  798. /**
  799. * @brief Get field wp_distance from high_latency message
  800. *
  801. * @return [m] distance to target
  802. */
  803. static inline uint16_t mavlink_msg_high_latency_get_wp_distance(const mavlink_message_t* msg)
  804. {
  805. return _MAV_RETURN_uint16_t(msg, 24);
  806. }
  807. /**
  808. * @brief Decode a high_latency message into a struct
  809. *
  810. * @param msg The message to decode
  811. * @param high_latency C-struct to decode the message contents into
  812. */
  813. static inline void mavlink_msg_high_latency_decode(const mavlink_message_t* msg, mavlink_high_latency_t* high_latency)
  814. {
  815. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  816. high_latency->custom_mode = mavlink_msg_high_latency_get_custom_mode(msg);
  817. high_latency->latitude = mavlink_msg_high_latency_get_latitude(msg);
  818. high_latency->longitude = mavlink_msg_high_latency_get_longitude(msg);
  819. high_latency->roll = mavlink_msg_high_latency_get_roll(msg);
  820. high_latency->pitch = mavlink_msg_high_latency_get_pitch(msg);
  821. high_latency->heading = mavlink_msg_high_latency_get_heading(msg);
  822. high_latency->heading_sp = mavlink_msg_high_latency_get_heading_sp(msg);
  823. high_latency->altitude_amsl = mavlink_msg_high_latency_get_altitude_amsl(msg);
  824. high_latency->altitude_sp = mavlink_msg_high_latency_get_altitude_sp(msg);
  825. high_latency->wp_distance = mavlink_msg_high_latency_get_wp_distance(msg);
  826. high_latency->base_mode = mavlink_msg_high_latency_get_base_mode(msg);
  827. high_latency->landed_state = mavlink_msg_high_latency_get_landed_state(msg);
  828. high_latency->throttle = mavlink_msg_high_latency_get_throttle(msg);
  829. high_latency->airspeed = mavlink_msg_high_latency_get_airspeed(msg);
  830. high_latency->airspeed_sp = mavlink_msg_high_latency_get_airspeed_sp(msg);
  831. high_latency->groundspeed = mavlink_msg_high_latency_get_groundspeed(msg);
  832. high_latency->climb_rate = mavlink_msg_high_latency_get_climb_rate(msg);
  833. high_latency->gps_nsat = mavlink_msg_high_latency_get_gps_nsat(msg);
  834. high_latency->gps_fix_type = mavlink_msg_high_latency_get_gps_fix_type(msg);
  835. high_latency->battery_remaining = mavlink_msg_high_latency_get_battery_remaining(msg);
  836. high_latency->temperature = mavlink_msg_high_latency_get_temperature(msg);
  837. high_latency->temperature_air = mavlink_msg_high_latency_get_temperature_air(msg);
  838. high_latency->failsafe = mavlink_msg_high_latency_get_failsafe(msg);
  839. high_latency->wp_num = mavlink_msg_high_latency_get_wp_num(msg);
  840. #else
  841. uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY_LEN;
  842. memset(high_latency, 0, MAVLINK_MSG_ID_HIGH_LATENCY_LEN);
  843. memcpy(high_latency, _MAV_PAYLOAD(msg), len);
  844. #endif
  845. }