mavlink_msg_set_position_target_local_ned.h 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588
  1. #pragma once
  2. // MESSAGE SET_POSITION_TARGET_LOCAL_NED PACKING
  3. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84
  4. typedef struct __mavlink_set_position_target_local_ned_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  6. float x; /*< [m] X Position in NED frame*/
  7. float y; /*< [m] Y Position in NED frame*/
  8. float z; /*< [m] Z Position in NED frame (note, altitude is negative in NED)*/
  9. float vx; /*< [m/s] X velocity in NED frame*/
  10. float vy; /*< [m/s] Y velocity in NED frame*/
  11. float vz; /*< [m/s] Z velocity in NED frame*/
  12. float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
  13. float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
  14. float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
  15. float yaw; /*< [rad] yaw setpoint*/
  16. float yaw_rate; /*< [rad/s] yaw rate setpoint*/
  17. uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/
  18. uint8_t target_system; /*< System ID*/
  19. uint8_t target_component; /*< Component ID*/
  20. uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/
  21. } mavlink_set_position_target_local_ned_t;
  22. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53
  23. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN 53
  24. #define MAVLINK_MSG_ID_84_LEN 53
  25. #define MAVLINK_MSG_ID_84_MIN_LEN 53
  26. #define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143
  27. #define MAVLINK_MSG_ID_84_CRC 143
  28. #if MAVLINK_COMMAND_24BIT
  29. #define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \
  30. 84, \
  31. "SET_POSITION_TARGET_LOCAL_NED", \
  32. 16, \
  33. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \
  34. { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \
  35. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \
  36. { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \
  37. { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \
  38. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \
  39. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \
  40. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \
  41. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \
  42. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \
  43. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \
  44. { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \
  45. { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \
  46. { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \
  47. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \
  48. { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \
  49. } \
  50. }
  51. #else
  52. #define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \
  53. "SET_POSITION_TARGET_LOCAL_NED", \
  54. 16, \
  55. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \
  56. { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \
  57. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \
  58. { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \
  59. { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \
  60. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \
  61. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \
  62. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \
  63. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \
  64. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \
  65. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \
  66. { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \
  67. { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \
  68. { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \
  69. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \
  70. { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \
  71. } \
  72. }
  73. #endif
  74. /**
  75. * @brief Pack a set_position_target_local_ned message
  76. * @param system_id ID of this system
  77. * @param component_id ID of this component (e.g. 200 for IMU)
  78. * @param msg The MAVLink message to compress the data into
  79. *
  80. * @param time_boot_ms [ms] Timestamp (time since system boot).
  81. * @param target_system System ID
  82. * @param target_component Component ID
  83. * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
  84. * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
  85. * @param x [m] X Position in NED frame
  86. * @param y [m] Y Position in NED frame
  87. * @param z [m] Z Position in NED frame (note, altitude is negative in NED)
  88. * @param vx [m/s] X velocity in NED frame
  89. * @param vy [m/s] Y velocity in NED frame
  90. * @param vz [m/s] Z velocity in NED frame
  91. * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  92. * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  93. * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  94. * @param yaw [rad] yaw setpoint
  95. * @param yaw_rate [rad/s] yaw rate setpoint
  96. * @return length of the message in bytes (excluding serial stream start sign)
  97. */
  98. static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  99. uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
  100. {
  101. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  102. char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
  103. _mav_put_uint32_t(buf, 0, time_boot_ms);
  104. _mav_put_float(buf, 4, x);
  105. _mav_put_float(buf, 8, y);
  106. _mav_put_float(buf, 12, z);
  107. _mav_put_float(buf, 16, vx);
  108. _mav_put_float(buf, 20, vy);
  109. _mav_put_float(buf, 24, vz);
  110. _mav_put_float(buf, 28, afx);
  111. _mav_put_float(buf, 32, afy);
  112. _mav_put_float(buf, 36, afz);
  113. _mav_put_float(buf, 40, yaw);
  114. _mav_put_float(buf, 44, yaw_rate);
  115. _mav_put_uint16_t(buf, 48, type_mask);
  116. _mav_put_uint8_t(buf, 50, target_system);
  117. _mav_put_uint8_t(buf, 51, target_component);
  118. _mav_put_uint8_t(buf, 52, coordinate_frame);
  119. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
  120. #else
  121. mavlink_set_position_target_local_ned_t packet;
  122. packet.time_boot_ms = time_boot_ms;
  123. packet.x = x;
  124. packet.y = y;
  125. packet.z = z;
  126. packet.vx = vx;
  127. packet.vy = vy;
  128. packet.vz = vz;
  129. packet.afx = afx;
  130. packet.afy = afy;
  131. packet.afz = afz;
  132. packet.yaw = yaw;
  133. packet.yaw_rate = yaw_rate;
  134. packet.type_mask = type_mask;
  135. packet.target_system = target_system;
  136. packet.target_component = target_component;
  137. packet.coordinate_frame = coordinate_frame;
  138. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
  139. #endif
  140. msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED;
  141. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
  142. }
  143. /**
  144. * @brief Pack a set_position_target_local_ned message on a channel
  145. * @param system_id ID of this system
  146. * @param component_id ID of this component (e.g. 200 for IMU)
  147. * @param chan The MAVLink channel this message will be sent over
  148. * @param msg The MAVLink message to compress the data into
  149. * @param time_boot_ms [ms] Timestamp (time since system boot).
  150. * @param target_system System ID
  151. * @param target_component Component ID
  152. * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
  153. * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
  154. * @param x [m] X Position in NED frame
  155. * @param y [m] Y Position in NED frame
  156. * @param z [m] Z Position in NED frame (note, altitude is negative in NED)
  157. * @param vx [m/s] X velocity in NED frame
  158. * @param vy [m/s] Y velocity in NED frame
  159. * @param vz [m/s] Z velocity in NED frame
  160. * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  161. * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  162. * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  163. * @param yaw [rad] yaw setpoint
  164. * @param yaw_rate [rad/s] yaw rate setpoint
  165. * @return length of the message in bytes (excluding serial stream start sign)
  166. */
  167. static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  168. mavlink_message_t* msg,
  169. uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
  170. {
  171. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  172. char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
  173. _mav_put_uint32_t(buf, 0, time_boot_ms);
  174. _mav_put_float(buf, 4, x);
  175. _mav_put_float(buf, 8, y);
  176. _mav_put_float(buf, 12, z);
  177. _mav_put_float(buf, 16, vx);
  178. _mav_put_float(buf, 20, vy);
  179. _mav_put_float(buf, 24, vz);
  180. _mav_put_float(buf, 28, afx);
  181. _mav_put_float(buf, 32, afy);
  182. _mav_put_float(buf, 36, afz);
  183. _mav_put_float(buf, 40, yaw);
  184. _mav_put_float(buf, 44, yaw_rate);
  185. _mav_put_uint16_t(buf, 48, type_mask);
  186. _mav_put_uint8_t(buf, 50, target_system);
  187. _mav_put_uint8_t(buf, 51, target_component);
  188. _mav_put_uint8_t(buf, 52, coordinate_frame);
  189. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
  190. #else
  191. mavlink_set_position_target_local_ned_t packet;
  192. packet.time_boot_ms = time_boot_ms;
  193. packet.x = x;
  194. packet.y = y;
  195. packet.z = z;
  196. packet.vx = vx;
  197. packet.vy = vy;
  198. packet.vz = vz;
  199. packet.afx = afx;
  200. packet.afy = afy;
  201. packet.afz = afz;
  202. packet.yaw = yaw;
  203. packet.yaw_rate = yaw_rate;
  204. packet.type_mask = type_mask;
  205. packet.target_system = target_system;
  206. packet.target_component = target_component;
  207. packet.coordinate_frame = coordinate_frame;
  208. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
  209. #endif
  210. msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED;
  211. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
  212. }
  213. /**
  214. * @brief Encode a set_position_target_local_ned struct
  215. *
  216. * @param system_id ID of this system
  217. * @param component_id ID of this component (e.g. 200 for IMU)
  218. * @param msg The MAVLink message to compress the data into
  219. * @param set_position_target_local_ned C-struct to read the message contents from
  220. */
  221. static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
  222. {
  223. return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate);
  224. }
  225. /**
  226. * @brief Encode a set_position_target_local_ned struct on a channel
  227. *
  228. * @param system_id ID of this system
  229. * @param component_id ID of this component (e.g. 200 for IMU)
  230. * @param chan The MAVLink channel this message will be sent over
  231. * @param msg The MAVLink message to compress the data into
  232. * @param set_position_target_local_ned C-struct to read the message contents from
  233. */
  234. static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
  235. {
  236. return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate);
  237. }
  238. /**
  239. * @brief Send a set_position_target_local_ned message
  240. * @param chan MAVLink channel to send the message
  241. *
  242. * @param time_boot_ms [ms] Timestamp (time since system boot).
  243. * @param target_system System ID
  244. * @param target_component Component ID
  245. * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
  246. * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
  247. * @param x [m] X Position in NED frame
  248. * @param y [m] Y Position in NED frame
  249. * @param z [m] Z Position in NED frame (note, altitude is negative in NED)
  250. * @param vx [m/s] X velocity in NED frame
  251. * @param vy [m/s] Y velocity in NED frame
  252. * @param vz [m/s] Z velocity in NED frame
  253. * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  254. * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  255. * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  256. * @param yaw [rad] yaw setpoint
  257. * @param yaw_rate [rad/s] yaw rate setpoint
  258. */
  259. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  260. static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
  261. {
  262. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  263. char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
  264. _mav_put_uint32_t(buf, 0, time_boot_ms);
  265. _mav_put_float(buf, 4, x);
  266. _mav_put_float(buf, 8, y);
  267. _mav_put_float(buf, 12, z);
  268. _mav_put_float(buf, 16, vx);
  269. _mav_put_float(buf, 20, vy);
  270. _mav_put_float(buf, 24, vz);
  271. _mav_put_float(buf, 28, afx);
  272. _mav_put_float(buf, 32, afy);
  273. _mav_put_float(buf, 36, afz);
  274. _mav_put_float(buf, 40, yaw);
  275. _mav_put_float(buf, 44, yaw_rate);
  276. _mav_put_uint16_t(buf, 48, type_mask);
  277. _mav_put_uint8_t(buf, 50, target_system);
  278. _mav_put_uint8_t(buf, 51, target_component);
  279. _mav_put_uint8_t(buf, 52, coordinate_frame);
  280. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
  281. #else
  282. mavlink_set_position_target_local_ned_t packet;
  283. packet.time_boot_ms = time_boot_ms;
  284. packet.x = x;
  285. packet.y = y;
  286. packet.z = z;
  287. packet.vx = vx;
  288. packet.vy = vy;
  289. packet.vz = vz;
  290. packet.afx = afx;
  291. packet.afy = afy;
  292. packet.afz = afz;
  293. packet.yaw = yaw;
  294. packet.yaw_rate = yaw_rate;
  295. packet.type_mask = type_mask;
  296. packet.target_system = target_system;
  297. packet.target_component = target_component;
  298. packet.coordinate_frame = coordinate_frame;
  299. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
  300. #endif
  301. }
  302. /**
  303. * @brief Send a set_position_target_local_ned message
  304. * @param chan MAVLink channel to send the message
  305. * @param struct The MAVLink struct to serialize
  306. */
  307. static inline void mavlink_msg_set_position_target_local_ned_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
  308. {
  309. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  310. mavlink_msg_set_position_target_local_ned_send(chan, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate);
  311. #else
  312. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)set_position_target_local_ned, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
  313. #endif
  314. }
  315. #if MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  316. /*
  317. This variant of _send() can be used to save stack space by re-using
  318. memory from the receive buffer. The caller provides a
  319. mavlink_message_t which is the size of a full mavlink message. This
  320. is usually the receive buffer for the channel, and allows a reply to an
  321. incoming message with minimum stack space usage.
  322. */
  323. static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
  324. {
  325. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  326. char *buf = (char *)msgbuf;
  327. _mav_put_uint32_t(buf, 0, time_boot_ms);
  328. _mav_put_float(buf, 4, x);
  329. _mav_put_float(buf, 8, y);
  330. _mav_put_float(buf, 12, z);
  331. _mav_put_float(buf, 16, vx);
  332. _mav_put_float(buf, 20, vy);
  333. _mav_put_float(buf, 24, vz);
  334. _mav_put_float(buf, 28, afx);
  335. _mav_put_float(buf, 32, afy);
  336. _mav_put_float(buf, 36, afz);
  337. _mav_put_float(buf, 40, yaw);
  338. _mav_put_float(buf, 44, yaw_rate);
  339. _mav_put_uint16_t(buf, 48, type_mask);
  340. _mav_put_uint8_t(buf, 50, target_system);
  341. _mav_put_uint8_t(buf, 51, target_component);
  342. _mav_put_uint8_t(buf, 52, coordinate_frame);
  343. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
  344. #else
  345. mavlink_set_position_target_local_ned_t *packet = (mavlink_set_position_target_local_ned_t *)msgbuf;
  346. packet->time_boot_ms = time_boot_ms;
  347. packet->x = x;
  348. packet->y = y;
  349. packet->z = z;
  350. packet->vx = vx;
  351. packet->vy = vy;
  352. packet->vz = vz;
  353. packet->afx = afx;
  354. packet->afy = afy;
  355. packet->afz = afz;
  356. packet->yaw = yaw;
  357. packet->yaw_rate = yaw_rate;
  358. packet->type_mask = type_mask;
  359. packet->target_system = target_system;
  360. packet->target_component = target_component;
  361. packet->coordinate_frame = coordinate_frame;
  362. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
  363. #endif
  364. }
  365. #endif
  366. #endif
  367. // MESSAGE SET_POSITION_TARGET_LOCAL_NED UNPACKING
  368. /**
  369. * @brief Get field time_boot_ms from set_position_target_local_ned message
  370. *
  371. * @return [ms] Timestamp (time since system boot).
  372. */
  373. static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg)
  374. {
  375. return _MAV_RETURN_uint32_t(msg, 0);
  376. }
  377. /**
  378. * @brief Get field target_system from set_position_target_local_ned message
  379. *
  380. * @return System ID
  381. */
  382. static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg)
  383. {
  384. return _MAV_RETURN_uint8_t(msg, 50);
  385. }
  386. /**
  387. * @brief Get field target_component from set_position_target_local_ned message
  388. *
  389. * @return Component ID
  390. */
  391. static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg)
  392. {
  393. return _MAV_RETURN_uint8_t(msg, 51);
  394. }
  395. /**
  396. * @brief Get field coordinate_frame from set_position_target_local_ned message
  397. *
  398. * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
  399. */
  400. static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
  401. {
  402. return _MAV_RETURN_uint8_t(msg, 52);
  403. }
  404. /**
  405. * @brief Get field type_mask from set_position_target_local_ned message
  406. *
  407. * @return Bitmap to indicate which dimensions should be ignored by the vehicle.
  408. */
  409. static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
  410. {
  411. return _MAV_RETURN_uint16_t(msg, 48);
  412. }
  413. /**
  414. * @brief Get field x from set_position_target_local_ned message
  415. *
  416. * @return [m] X Position in NED frame
  417. */
  418. static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg)
  419. {
  420. return _MAV_RETURN_float(msg, 4);
  421. }
  422. /**
  423. * @brief Get field y from set_position_target_local_ned message
  424. *
  425. * @return [m] Y Position in NED frame
  426. */
  427. static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg)
  428. {
  429. return _MAV_RETURN_float(msg, 8);
  430. }
  431. /**
  432. * @brief Get field z from set_position_target_local_ned message
  433. *
  434. * @return [m] Z Position in NED frame (note, altitude is negative in NED)
  435. */
  436. static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg)
  437. {
  438. return _MAV_RETURN_float(msg, 12);
  439. }
  440. /**
  441. * @brief Get field vx from set_position_target_local_ned message
  442. *
  443. * @return [m/s] X velocity in NED frame
  444. */
  445. static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg)
  446. {
  447. return _MAV_RETURN_float(msg, 16);
  448. }
  449. /**
  450. * @brief Get field vy from set_position_target_local_ned message
  451. *
  452. * @return [m/s] Y velocity in NED frame
  453. */
  454. static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg)
  455. {
  456. return _MAV_RETURN_float(msg, 20);
  457. }
  458. /**
  459. * @brief Get field vz from set_position_target_local_ned message
  460. *
  461. * @return [m/s] Z velocity in NED frame
  462. */
  463. static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg)
  464. {
  465. return _MAV_RETURN_float(msg, 24);
  466. }
  467. /**
  468. * @brief Get field afx from set_position_target_local_ned message
  469. *
  470. * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  471. */
  472. static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg)
  473. {
  474. return _MAV_RETURN_float(msg, 28);
  475. }
  476. /**
  477. * @brief Get field afy from set_position_target_local_ned message
  478. *
  479. * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  480. */
  481. static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg)
  482. {
  483. return _MAV_RETURN_float(msg, 32);
  484. }
  485. /**
  486. * @brief Get field afz from set_position_target_local_ned message
  487. *
  488. * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
  489. */
  490. static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg)
  491. {
  492. return _MAV_RETURN_float(msg, 36);
  493. }
  494. /**
  495. * @brief Get field yaw from set_position_target_local_ned message
  496. *
  497. * @return [rad] yaw setpoint
  498. */
  499. static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
  500. {
  501. return _MAV_RETURN_float(msg, 40);
  502. }
  503. /**
  504. * @brief Get field yaw_rate from set_position_target_local_ned message
  505. *
  506. * @return [rad/s] yaw rate setpoint
  507. */
  508. static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
  509. {
  510. return _MAV_RETURN_float(msg, 44);
  511. }
  512. /**
  513. * @brief Decode a set_position_target_local_ned message into a struct
  514. *
  515. * @param msg The message to decode
  516. * @param set_position_target_local_ned C-struct to decode the message contents into
  517. */
  518. static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
  519. {
  520. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  521. set_position_target_local_ned->time_boot_ms = mavlink_msg_set_position_target_local_ned_get_time_boot_ms(msg);
  522. set_position_target_local_ned->x = mavlink_msg_set_position_target_local_ned_get_x(msg);
  523. set_position_target_local_ned->y = mavlink_msg_set_position_target_local_ned_get_y(msg);
  524. set_position_target_local_ned->z = mavlink_msg_set_position_target_local_ned_get_z(msg);
  525. set_position_target_local_ned->vx = mavlink_msg_set_position_target_local_ned_get_vx(msg);
  526. set_position_target_local_ned->vy = mavlink_msg_set_position_target_local_ned_get_vy(msg);
  527. set_position_target_local_ned->vz = mavlink_msg_set_position_target_local_ned_get_vz(msg);
  528. set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg);
  529. set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg);
  530. set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg);
  531. set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg);
  532. set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg);
  533. set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg);
  534. set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg);
  535. set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg);
  536. set_position_target_local_ned->coordinate_frame = mavlink_msg_set_position_target_local_ned_get_coordinate_frame(msg);
  537. #else
  538. uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN;
  539. memset(set_position_target_local_ned, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
  540. memcpy(set_position_target_local_ned, _MAV_PAYLOAD(msg), len);
  541. #endif
  542. }