mavlink_msg_command_long.h 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540
  1. #pragma once
  2. // MESSAGE COMMAND_LONG PACKING
  3. #define MAVLINK_MSG_ID_COMMAND_LONG 76
  4. typedef struct __mavlink_command_long_t {
  5. float param1; /*< Parameter 1 (for the specific command).*/
  6. float param2; /*< Parameter 2 (for the specific command).*/
  7. float param3; /*< Parameter 3 (for the specific command).*/
  8. float param4; /*< Parameter 4 (for the specific command).*/
  9. float param5; /*< Parameter 5 (for the specific command).*/
  10. float param6; /*< Parameter 6 (for the specific command).*/
  11. float param7; /*< Parameter 7 (for the specific command).*/
  12. uint16_t command; /*< Command ID (of command to send).*/
  13. uint8_t target_system; /*< System which should execute the command*/
  14. uint8_t target_component; /*< Component which should execute the command, 0 for all components*/
  15. uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/
  16. } mavlink_command_long_t;
  17. #define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33
  18. #define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33
  19. #define MAVLINK_MSG_ID_76_LEN 33
  20. #define MAVLINK_MSG_ID_76_MIN_LEN 33
  21. #define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152
  22. #define MAVLINK_MSG_ID_76_CRC 152
  23. #if MAVLINK_COMMAND_24BIT
  24. #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
  25. 76, \
  26. "COMMAND_LONG", \
  27. 11, \
  28. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
  29. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
  30. { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
  31. { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
  32. { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
  33. { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
  34. { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
  35. { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
  36. { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
  37. { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
  38. { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
  39. } \
  40. }
  41. #else
  42. #define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
  43. "COMMAND_LONG", \
  44. 11, \
  45. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
  46. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
  47. { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
  48. { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
  49. { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
  50. { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
  51. { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
  52. { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
  53. { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
  54. { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
  55. { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
  56. } \
  57. }
  58. #endif
  59. /**
  60. * @brief Pack a command_long message
  61. * @param system_id ID of this system
  62. * @param component_id ID of this component (e.g. 200 for IMU)
  63. * @param msg The MAVLink message to compress the data into
  64. *
  65. * @param target_system System which should execute the command
  66. * @param target_component Component which should execute the command, 0 for all components
  67. * @param command Command ID (of command to send).
  68. * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
  69. * @param param1 Parameter 1 (for the specific command).
  70. * @param param2 Parameter 2 (for the specific command).
  71. * @param param3 Parameter 3 (for the specific command).
  72. * @param param4 Parameter 4 (for the specific command).
  73. * @param param5 Parameter 5 (for the specific command).
  74. * @param param6 Parameter 6 (for the specific command).
  75. * @param param7 Parameter 7 (for the specific command).
  76. * @return length of the message in bytes (excluding serial stream start sign)
  77. */
  78. static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  79. uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
  80. {
  81. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  82. char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN];
  83. _mav_put_float(buf, 0, param1);
  84. _mav_put_float(buf, 4, param2);
  85. _mav_put_float(buf, 8, param3);
  86. _mav_put_float(buf, 12, param4);
  87. _mav_put_float(buf, 16, param5);
  88. _mav_put_float(buf, 20, param6);
  89. _mav_put_float(buf, 24, param7);
  90. _mav_put_uint16_t(buf, 28, command);
  91. _mav_put_uint8_t(buf, 30, target_system);
  92. _mav_put_uint8_t(buf, 31, target_component);
  93. _mav_put_uint8_t(buf, 32, confirmation);
  94. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  95. #else
  96. mavlink_command_long_t packet;
  97. packet.param1 = param1;
  98. packet.param2 = param2;
  99. packet.param3 = param3;
  100. packet.param4 = param4;
  101. packet.param5 = param5;
  102. packet.param6 = param6;
  103. packet.param7 = param7;
  104. packet.command = command;
  105. packet.target_system = target_system;
  106. packet.target_component = target_component;
  107. packet.confirmation = confirmation;
  108. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  109. #endif
  110. msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG;
  111. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  112. }
  113. /**
  114. * @brief Pack a command_long message
  115. * @param system_id ID of this system
  116. * @param component_id ID of this component (e.g. 200 for IMU)
  117. * @param status MAVLink status structure
  118. * @param msg The MAVLink message to compress the data into
  119. *
  120. * @param target_system System which should execute the command
  121. * @param target_component Component which should execute the command, 0 for all components
  122. * @param command Command ID (of command to send).
  123. * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
  124. * @param param1 Parameter 1 (for the specific command).
  125. * @param param2 Parameter 2 (for the specific command).
  126. * @param param3 Parameter 3 (for the specific command).
  127. * @param param4 Parameter 4 (for the specific command).
  128. * @param param5 Parameter 5 (for the specific command).
  129. * @param param6 Parameter 6 (for the specific command).
  130. * @param param7 Parameter 7 (for the specific command).
  131. * @return length of the message in bytes (excluding serial stream start sign)
  132. */
  133. static inline uint16_t mavlink_msg_command_long_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  134. uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
  135. {
  136. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  137. char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN];
  138. _mav_put_float(buf, 0, param1);
  139. _mav_put_float(buf, 4, param2);
  140. _mav_put_float(buf, 8, param3);
  141. _mav_put_float(buf, 12, param4);
  142. _mav_put_float(buf, 16, param5);
  143. _mav_put_float(buf, 20, param6);
  144. _mav_put_float(buf, 24, param7);
  145. _mav_put_uint16_t(buf, 28, command);
  146. _mav_put_uint8_t(buf, 30, target_system);
  147. _mav_put_uint8_t(buf, 31, target_component);
  148. _mav_put_uint8_t(buf, 32, confirmation);
  149. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  150. #else
  151. mavlink_command_long_t packet;
  152. packet.param1 = param1;
  153. packet.param2 = param2;
  154. packet.param3 = param3;
  155. packet.param4 = param4;
  156. packet.param5 = param5;
  157. packet.param6 = param6;
  158. packet.param7 = param7;
  159. packet.command = command;
  160. packet.target_system = target_system;
  161. packet.target_component = target_component;
  162. packet.confirmation = confirmation;
  163. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  164. #endif
  165. msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG;
  166. #if MAVLINK_CRC_EXTRA
  167. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  168. #else
  169. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  170. #endif
  171. }
  172. /**
  173. * @brief Pack a command_long message on a channel
  174. * @param system_id ID of this system
  175. * @param component_id ID of this component (e.g. 200 for IMU)
  176. * @param chan The MAVLink channel this message will be sent over
  177. * @param msg The MAVLink message to compress the data into
  178. * @param target_system System which should execute the command
  179. * @param target_component Component which should execute the command, 0 for all components
  180. * @param command Command ID (of command to send).
  181. * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
  182. * @param param1 Parameter 1 (for the specific command).
  183. * @param param2 Parameter 2 (for the specific command).
  184. * @param param3 Parameter 3 (for the specific command).
  185. * @param param4 Parameter 4 (for the specific command).
  186. * @param param5 Parameter 5 (for the specific command).
  187. * @param param6 Parameter 6 (for the specific command).
  188. * @param param7 Parameter 7 (for the specific command).
  189. * @return length of the message in bytes (excluding serial stream start sign)
  190. */
  191. static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  192. mavlink_message_t* msg,
  193. uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7)
  194. {
  195. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  196. char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN];
  197. _mav_put_float(buf, 0, param1);
  198. _mav_put_float(buf, 4, param2);
  199. _mav_put_float(buf, 8, param3);
  200. _mav_put_float(buf, 12, param4);
  201. _mav_put_float(buf, 16, param5);
  202. _mav_put_float(buf, 20, param6);
  203. _mav_put_float(buf, 24, param7);
  204. _mav_put_uint16_t(buf, 28, command);
  205. _mav_put_uint8_t(buf, 30, target_system);
  206. _mav_put_uint8_t(buf, 31, target_component);
  207. _mav_put_uint8_t(buf, 32, confirmation);
  208. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  209. #else
  210. mavlink_command_long_t packet;
  211. packet.param1 = param1;
  212. packet.param2 = param2;
  213. packet.param3 = param3;
  214. packet.param4 = param4;
  215. packet.param5 = param5;
  216. packet.param6 = param6;
  217. packet.param7 = param7;
  218. packet.command = command;
  219. packet.target_system = target_system;
  220. packet.target_component = target_component;
  221. packet.confirmation = confirmation;
  222. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  223. #endif
  224. msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG;
  225. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  226. }
  227. /**
  228. * @brief Encode a command_long struct
  229. *
  230. * @param system_id ID of this system
  231. * @param component_id ID of this component (e.g. 200 for IMU)
  232. * @param msg The MAVLink message to compress the data into
  233. * @param command_long C-struct to read the message contents from
  234. */
  235. static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long)
  236. {
  237. return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
  238. }
  239. /**
  240. * @brief Encode a command_long struct on a channel
  241. *
  242. * @param system_id ID of this system
  243. * @param component_id ID of this component (e.g. 200 for IMU)
  244. * @param chan The MAVLink channel this message will be sent over
  245. * @param msg The MAVLink message to compress the data into
  246. * @param command_long C-struct to read the message contents from
  247. */
  248. static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long)
  249. {
  250. return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
  251. }
  252. /**
  253. * @brief Encode a command_long struct with provided status structure
  254. *
  255. * @param system_id ID of this system
  256. * @param component_id ID of this component (e.g. 200 for IMU)
  257. * @param status MAVLink status structure
  258. * @param msg The MAVLink message to compress the data into
  259. * @param command_long C-struct to read the message contents from
  260. */
  261. static inline uint16_t mavlink_msg_command_long_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_command_long_t* command_long)
  262. {
  263. return mavlink_msg_command_long_pack_status(system_id, component_id, _status, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
  264. }
  265. /**
  266. * @brief Send a command_long message
  267. * @param chan MAVLink channel to send the message
  268. *
  269. * @param target_system System which should execute the command
  270. * @param target_component Component which should execute the command, 0 for all components
  271. * @param command Command ID (of command to send).
  272. * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
  273. * @param param1 Parameter 1 (for the specific command).
  274. * @param param2 Parameter 2 (for the specific command).
  275. * @param param3 Parameter 3 (for the specific command).
  276. * @param param4 Parameter 4 (for the specific command).
  277. * @param param5 Parameter 5 (for the specific command).
  278. * @param param6 Parameter 6 (for the specific command).
  279. * @param param7 Parameter 7 (for the specific command).
  280. */
  281. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  282. static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
  283. {
  284. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  285. char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN];
  286. _mav_put_float(buf, 0, param1);
  287. _mav_put_float(buf, 4, param2);
  288. _mav_put_float(buf, 8, param3);
  289. _mav_put_float(buf, 12, param4);
  290. _mav_put_float(buf, 16, param5);
  291. _mav_put_float(buf, 20, param6);
  292. _mav_put_float(buf, 24, param7);
  293. _mav_put_uint16_t(buf, 28, command);
  294. _mav_put_uint8_t(buf, 30, target_system);
  295. _mav_put_uint8_t(buf, 31, target_component);
  296. _mav_put_uint8_t(buf, 32, confirmation);
  297. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  298. #else
  299. mavlink_command_long_t packet;
  300. packet.param1 = param1;
  301. packet.param2 = param2;
  302. packet.param3 = param3;
  303. packet.param4 = param4;
  304. packet.param5 = param5;
  305. packet.param6 = param6;
  306. packet.param7 = param7;
  307. packet.command = command;
  308. packet.target_system = target_system;
  309. packet.target_component = target_component;
  310. packet.confirmation = confirmation;
  311. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  312. #endif
  313. }
  314. /**
  315. * @brief Send a command_long message
  316. * @param chan MAVLink channel to send the message
  317. * @param struct The MAVLink struct to serialize
  318. */
  319. static inline void mavlink_msg_command_long_send_struct(mavlink_channel_t chan, const mavlink_command_long_t* command_long)
  320. {
  321. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  322. mavlink_msg_command_long_send(chan, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
  323. #else
  324. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)command_long, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  325. #endif
  326. }
  327. #if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  328. /*
  329. This variant of _send() can be used to save stack space by re-using
  330. memory from the receive buffer. The caller provides a
  331. mavlink_message_t which is the size of a full mavlink message. This
  332. is usually the receive buffer for the channel, and allows a reply to an
  333. incoming message with minimum stack space usage.
  334. */
  335. static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
  336. {
  337. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  338. char *buf = (char *)msgbuf;
  339. _mav_put_float(buf, 0, param1);
  340. _mav_put_float(buf, 4, param2);
  341. _mav_put_float(buf, 8, param3);
  342. _mav_put_float(buf, 12, param4);
  343. _mav_put_float(buf, 16, param5);
  344. _mav_put_float(buf, 20, param6);
  345. _mav_put_float(buf, 24, param7);
  346. _mav_put_uint16_t(buf, 28, command);
  347. _mav_put_uint8_t(buf, 30, target_system);
  348. _mav_put_uint8_t(buf, 31, target_component);
  349. _mav_put_uint8_t(buf, 32, confirmation);
  350. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  351. #else
  352. mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf;
  353. packet->param1 = param1;
  354. packet->param2 = param2;
  355. packet->param3 = param3;
  356. packet->param4 = param4;
  357. packet->param5 = param5;
  358. packet->param6 = param6;
  359. packet->param7 = param7;
  360. packet->command = command;
  361. packet->target_system = target_system;
  362. packet->target_component = target_component;
  363. packet->confirmation = confirmation;
  364. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
  365. #endif
  366. }
  367. #endif
  368. #endif
  369. // MESSAGE COMMAND_LONG UNPACKING
  370. /**
  371. * @brief Get field target_system from command_long message
  372. *
  373. * @return System which should execute the command
  374. */
  375. static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg)
  376. {
  377. return _MAV_RETURN_uint8_t(msg, 30);
  378. }
  379. /**
  380. * @brief Get field target_component from command_long message
  381. *
  382. * @return Component which should execute the command, 0 for all components
  383. */
  384. static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg)
  385. {
  386. return _MAV_RETURN_uint8_t(msg, 31);
  387. }
  388. /**
  389. * @brief Get field command from command_long message
  390. *
  391. * @return Command ID (of command to send).
  392. */
  393. static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg)
  394. {
  395. return _MAV_RETURN_uint16_t(msg, 28);
  396. }
  397. /**
  398. * @brief Get field confirmation from command_long message
  399. *
  400. * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
  401. */
  402. static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg)
  403. {
  404. return _MAV_RETURN_uint8_t(msg, 32);
  405. }
  406. /**
  407. * @brief Get field param1 from command_long message
  408. *
  409. * @return Parameter 1 (for the specific command).
  410. */
  411. static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg)
  412. {
  413. return _MAV_RETURN_float(msg, 0);
  414. }
  415. /**
  416. * @brief Get field param2 from command_long message
  417. *
  418. * @return Parameter 2 (for the specific command).
  419. */
  420. static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg)
  421. {
  422. return _MAV_RETURN_float(msg, 4);
  423. }
  424. /**
  425. * @brief Get field param3 from command_long message
  426. *
  427. * @return Parameter 3 (for the specific command).
  428. */
  429. static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg)
  430. {
  431. return _MAV_RETURN_float(msg, 8);
  432. }
  433. /**
  434. * @brief Get field param4 from command_long message
  435. *
  436. * @return Parameter 4 (for the specific command).
  437. */
  438. static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg)
  439. {
  440. return _MAV_RETURN_float(msg, 12);
  441. }
  442. /**
  443. * @brief Get field param5 from command_long message
  444. *
  445. * @return Parameter 5 (for the specific command).
  446. */
  447. static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg)
  448. {
  449. return _MAV_RETURN_float(msg, 16);
  450. }
  451. /**
  452. * @brief Get field param6 from command_long message
  453. *
  454. * @return Parameter 6 (for the specific command).
  455. */
  456. static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg)
  457. {
  458. return _MAV_RETURN_float(msg, 20);
  459. }
  460. /**
  461. * @brief Get field param7 from command_long message
  462. *
  463. * @return Parameter 7 (for the specific command).
  464. */
  465. static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg)
  466. {
  467. return _MAV_RETURN_float(msg, 24);
  468. }
  469. /**
  470. * @brief Decode a command_long message into a struct
  471. *
  472. * @param msg The message to decode
  473. * @param command_long C-struct to decode the message contents into
  474. */
  475. static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long)
  476. {
  477. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  478. command_long->param1 = mavlink_msg_command_long_get_param1(msg);
  479. command_long->param2 = mavlink_msg_command_long_get_param2(msg);
  480. command_long->param3 = mavlink_msg_command_long_get_param3(msg);
  481. command_long->param4 = mavlink_msg_command_long_get_param4(msg);
  482. command_long->param5 = mavlink_msg_command_long_get_param5(msg);
  483. command_long->param6 = mavlink_msg_command_long_get_param6(msg);
  484. command_long->param7 = mavlink_msg_command_long_get_param7(msg);
  485. command_long->command = mavlink_msg_command_long_get_command(msg);
  486. command_long->target_system = mavlink_msg_command_long_get_target_system(msg);
  487. command_long->target_component = mavlink_msg_command_long_get_target_component(msg);
  488. command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg);
  489. #else
  490. uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_LONG_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_LONG_LEN;
  491. memset(command_long, 0, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
  492. memcpy(command_long, _MAV_PAYLOAD(msg), len);
  493. #endif
  494. }