mavlink_msg_position_target_local_ned.h 26 KB

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