mavlink_msg_set_home_position.h 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480
  1. #pragma once
  2. // MESSAGE SET_HOME_POSITION PACKING
  3. #define MAVLINK_MSG_ID_SET_HOME_POSITION 243
  4. MAVPACKED(
  5. typedef struct __mavlink_set_home_position_t {
  6. int32_t latitude; /*< [degE7] Latitude (WGS84)*/
  7. int32_t longitude; /*< [degE7] Longitude (WGS84)*/
  8. int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/
  9. float x; /*< [m] Local X position of this position in the local coordinate frame (NED)*/
  10. float y; /*< [m] Local Y position of this position in the local coordinate frame (NED)*/
  11. float z; /*< [m] Local Z position of this position in the local coordinate frame (NED: positive "down")*/
  12. float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/
  13. float approach_x; /*< [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
  14. float approach_y; /*< [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
  15. float approach_z; /*< [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
  16. uint8_t target_system; /*< System ID.*/
  17. uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
  18. }) mavlink_set_home_position_t;
  19. #define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 61
  20. #define MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN 53
  21. #define MAVLINK_MSG_ID_243_LEN 61
  22. #define MAVLINK_MSG_ID_243_MIN_LEN 53
  23. #define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85
  24. #define MAVLINK_MSG_ID_243_CRC 85
  25. #define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4
  26. #if MAVLINK_COMMAND_24BIT
  27. #define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \
  28. 243, \
  29. "SET_HOME_POSITION", \
  30. 12, \
  31. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \
  32. { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \
  33. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \
  34. { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \
  35. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \
  36. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \
  37. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \
  38. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \
  39. { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \
  40. { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \
  41. { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \
  42. { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 53, offsetof(mavlink_set_home_position_t, time_usec) }, \
  43. } \
  44. }
  45. #else
  46. #define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \
  47. "SET_HOME_POSITION", \
  48. 12, \
  49. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \
  50. { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \
  51. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \
  52. { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \
  53. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \
  54. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \
  55. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \
  56. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \
  57. { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \
  58. { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \
  59. { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \
  60. { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 53, offsetof(mavlink_set_home_position_t, time_usec) }, \
  61. } \
  62. }
  63. #endif
  64. /**
  65. * @brief Pack a set_home_position message
  66. * @param system_id ID of this system
  67. * @param component_id ID of this component (e.g. 200 for IMU)
  68. * @param msg The MAVLink message to compress the data into
  69. *
  70. * @param target_system System ID.
  71. * @param latitude [degE7] Latitude (WGS84)
  72. * @param longitude [degE7] Longitude (WGS84)
  73. * @param altitude [mm] Altitude (MSL). Positive for up.
  74. * @param x [m] Local X position of this position in the local coordinate frame (NED)
  75. * @param y [m] Local Y position of this position in the local coordinate frame (NED)
  76. * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  77. * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  78. * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  79. * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  80. * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  81. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  82. * @return length of the message in bytes (excluding serial stream start sign)
  83. */
  84. static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  85. uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec)
  86. {
  87. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  88. char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
  89. _mav_put_int32_t(buf, 0, latitude);
  90. _mav_put_int32_t(buf, 4, longitude);
  91. _mav_put_int32_t(buf, 8, altitude);
  92. _mav_put_float(buf, 12, x);
  93. _mav_put_float(buf, 16, y);
  94. _mav_put_float(buf, 20, z);
  95. _mav_put_float(buf, 40, approach_x);
  96. _mav_put_float(buf, 44, approach_y);
  97. _mav_put_float(buf, 48, approach_z);
  98. _mav_put_uint8_t(buf, 52, target_system);
  99. _mav_put_uint64_t(buf, 53, time_usec);
  100. _mav_put_float_array(buf, 24, q, 4);
  101. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  102. #else
  103. mavlink_set_home_position_t packet;
  104. packet.latitude = latitude;
  105. packet.longitude = longitude;
  106. packet.altitude = altitude;
  107. packet.x = x;
  108. packet.y = y;
  109. packet.z = z;
  110. packet.approach_x = approach_x;
  111. packet.approach_y = approach_y;
  112. packet.approach_z = approach_z;
  113. packet.target_system = target_system;
  114. packet.time_usec = time_usec;
  115. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  116. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  117. #endif
  118. msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION;
  119. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  120. }
  121. /**
  122. * @brief Pack a set_home_position message on a channel
  123. * @param system_id ID of this system
  124. * @param component_id ID of this component (e.g. 200 for IMU)
  125. * @param chan The MAVLink channel this message will be sent over
  126. * @param msg The MAVLink message to compress the data into
  127. * @param target_system System ID.
  128. * @param latitude [degE7] Latitude (WGS84)
  129. * @param longitude [degE7] Longitude (WGS84)
  130. * @param altitude [mm] Altitude (MSL). Positive for up.
  131. * @param x [m] Local X position of this position in the local coordinate frame (NED)
  132. * @param y [m] Local Y position of this position in the local coordinate frame (NED)
  133. * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  134. * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  135. * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  136. * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  137. * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  138. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  139. * @return length of the message in bytes (excluding serial stream start sign)
  140. */
  141. static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  142. mavlink_message_t* msg,
  143. uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z,uint64_t time_usec)
  144. {
  145. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  146. char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
  147. _mav_put_int32_t(buf, 0, latitude);
  148. _mav_put_int32_t(buf, 4, longitude);
  149. _mav_put_int32_t(buf, 8, altitude);
  150. _mav_put_float(buf, 12, x);
  151. _mav_put_float(buf, 16, y);
  152. _mav_put_float(buf, 20, z);
  153. _mav_put_float(buf, 40, approach_x);
  154. _mav_put_float(buf, 44, approach_y);
  155. _mav_put_float(buf, 48, approach_z);
  156. _mav_put_uint8_t(buf, 52, target_system);
  157. _mav_put_uint64_t(buf, 53, time_usec);
  158. _mav_put_float_array(buf, 24, q, 4);
  159. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  160. #else
  161. mavlink_set_home_position_t packet;
  162. packet.latitude = latitude;
  163. packet.longitude = longitude;
  164. packet.altitude = altitude;
  165. packet.x = x;
  166. packet.y = y;
  167. packet.z = z;
  168. packet.approach_x = approach_x;
  169. packet.approach_y = approach_y;
  170. packet.approach_z = approach_z;
  171. packet.target_system = target_system;
  172. packet.time_usec = time_usec;
  173. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  174. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  175. #endif
  176. msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION;
  177. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  178. }
  179. /**
  180. * @brief Encode a set_home_position struct
  181. *
  182. * @param system_id ID of this system
  183. * @param component_id ID of this component (e.g. 200 for IMU)
  184. * @param msg The MAVLink message to compress the data into
  185. * @param set_home_position C-struct to read the message contents from
  186. */
  187. static inline uint16_t mavlink_msg_set_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position)
  188. {
  189. return mavlink_msg_set_home_position_pack(system_id, component_id, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z, set_home_position->time_usec);
  190. }
  191. /**
  192. * @brief Encode a set_home_position struct on a channel
  193. *
  194. * @param system_id ID of this system
  195. * @param component_id ID of this component (e.g. 200 for IMU)
  196. * @param chan The MAVLink channel this message will be sent over
  197. * @param msg The MAVLink message to compress the data into
  198. * @param set_home_position C-struct to read the message contents from
  199. */
  200. static inline uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position)
  201. {
  202. return mavlink_msg_set_home_position_pack_chan(system_id, component_id, chan, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z, set_home_position->time_usec);
  203. }
  204. /**
  205. * @brief Send a set_home_position message
  206. * @param chan MAVLink channel to send the message
  207. *
  208. * @param target_system System ID.
  209. * @param latitude [degE7] Latitude (WGS84)
  210. * @param longitude [degE7] Longitude (WGS84)
  211. * @param altitude [mm] Altitude (MSL). Positive for up.
  212. * @param x [m] Local X position of this position in the local coordinate frame (NED)
  213. * @param y [m] Local Y position of this position in the local coordinate frame (NED)
  214. * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  215. * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  216. * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  217. * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  218. * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  219. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  220. */
  221. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  222. static inline void mavlink_msg_set_home_position_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec)
  223. {
  224. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  225. char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
  226. _mav_put_int32_t(buf, 0, latitude);
  227. _mav_put_int32_t(buf, 4, longitude);
  228. _mav_put_int32_t(buf, 8, altitude);
  229. _mav_put_float(buf, 12, x);
  230. _mav_put_float(buf, 16, y);
  231. _mav_put_float(buf, 20, z);
  232. _mav_put_float(buf, 40, approach_x);
  233. _mav_put_float(buf, 44, approach_y);
  234. _mav_put_float(buf, 48, approach_z);
  235. _mav_put_uint8_t(buf, 52, target_system);
  236. _mav_put_uint64_t(buf, 53, time_usec);
  237. _mav_put_float_array(buf, 24, q, 4);
  238. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  239. #else
  240. mavlink_set_home_position_t packet;
  241. packet.latitude = latitude;
  242. packet.longitude = longitude;
  243. packet.altitude = altitude;
  244. packet.x = x;
  245. packet.y = y;
  246. packet.z = z;
  247. packet.approach_x = approach_x;
  248. packet.approach_y = approach_y;
  249. packet.approach_z = approach_z;
  250. packet.target_system = target_system;
  251. packet.time_usec = time_usec;
  252. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  253. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  254. #endif
  255. }
  256. /**
  257. * @brief Send a set_home_position message
  258. * @param chan MAVLink channel to send the message
  259. * @param struct The MAVLink struct to serialize
  260. */
  261. static inline void mavlink_msg_set_home_position_send_struct(mavlink_channel_t chan, const mavlink_set_home_position_t* set_home_position)
  262. {
  263. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  264. mavlink_msg_set_home_position_send(chan, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z, set_home_position->time_usec);
  265. #else
  266. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)set_home_position, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  267. #endif
  268. }
  269. #if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  270. /*
  271. This variant of _send() can be used to save stack space by re-using
  272. memory from the receive buffer. The caller provides a
  273. mavlink_message_t which is the size of a full mavlink message. This
  274. is usually the receive buffer for the channel, and allows a reply to an
  275. incoming message with minimum stack space usage.
  276. */
  277. static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec)
  278. {
  279. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  280. char *buf = (char *)msgbuf;
  281. _mav_put_int32_t(buf, 0, latitude);
  282. _mav_put_int32_t(buf, 4, longitude);
  283. _mav_put_int32_t(buf, 8, altitude);
  284. _mav_put_float(buf, 12, x);
  285. _mav_put_float(buf, 16, y);
  286. _mav_put_float(buf, 20, z);
  287. _mav_put_float(buf, 40, approach_x);
  288. _mav_put_float(buf, 44, approach_y);
  289. _mav_put_float(buf, 48, approach_z);
  290. _mav_put_uint8_t(buf, 52, target_system);
  291. _mav_put_uint64_t(buf, 53, time_usec);
  292. _mav_put_float_array(buf, 24, q, 4);
  293. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  294. #else
  295. mavlink_set_home_position_t *packet = (mavlink_set_home_position_t *)msgbuf;
  296. packet->latitude = latitude;
  297. packet->longitude = longitude;
  298. packet->altitude = altitude;
  299. packet->x = x;
  300. packet->y = y;
  301. packet->z = z;
  302. packet->approach_x = approach_x;
  303. packet->approach_y = approach_y;
  304. packet->approach_z = approach_z;
  305. packet->target_system = target_system;
  306. packet->time_usec = time_usec;
  307. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  308. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  309. #endif
  310. }
  311. #endif
  312. #endif
  313. // MESSAGE SET_HOME_POSITION UNPACKING
  314. /**
  315. * @brief Get field target_system from set_home_position message
  316. *
  317. * @return System ID.
  318. */
  319. static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg)
  320. {
  321. return _MAV_RETURN_uint8_t(msg, 52);
  322. }
  323. /**
  324. * @brief Get field latitude from set_home_position message
  325. *
  326. * @return [degE7] Latitude (WGS84)
  327. */
  328. static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg)
  329. {
  330. return _MAV_RETURN_int32_t(msg, 0);
  331. }
  332. /**
  333. * @brief Get field longitude from set_home_position message
  334. *
  335. * @return [degE7] Longitude (WGS84)
  336. */
  337. static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg)
  338. {
  339. return _MAV_RETURN_int32_t(msg, 4);
  340. }
  341. /**
  342. * @brief Get field altitude from set_home_position message
  343. *
  344. * @return [mm] Altitude (MSL). Positive for up.
  345. */
  346. static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg)
  347. {
  348. return _MAV_RETURN_int32_t(msg, 8);
  349. }
  350. /**
  351. * @brief Get field x from set_home_position message
  352. *
  353. * @return [m] Local X position of this position in the local coordinate frame (NED)
  354. */
  355. static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg)
  356. {
  357. return _MAV_RETURN_float(msg, 12);
  358. }
  359. /**
  360. * @brief Get field y from set_home_position message
  361. *
  362. * @return [m] Local Y position of this position in the local coordinate frame (NED)
  363. */
  364. static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg)
  365. {
  366. return _MAV_RETURN_float(msg, 16);
  367. }
  368. /**
  369. * @brief Get field z from set_home_position message
  370. *
  371. * @return [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  372. */
  373. static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg)
  374. {
  375. return _MAV_RETURN_float(msg, 20);
  376. }
  377. /**
  378. * @brief Get field q from set_home_position message
  379. *
  380. * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  381. */
  382. static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q)
  383. {
  384. return _MAV_RETURN_float_array(msg, q, 4, 24);
  385. }
  386. /**
  387. * @brief Get field approach_x from set_home_position message
  388. *
  389. * @return [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  390. */
  391. static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg)
  392. {
  393. return _MAV_RETURN_float(msg, 40);
  394. }
  395. /**
  396. * @brief Get field approach_y from set_home_position message
  397. *
  398. * @return [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  399. */
  400. static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg)
  401. {
  402. return _MAV_RETURN_float(msg, 44);
  403. }
  404. /**
  405. * @brief Get field approach_z from set_home_position message
  406. *
  407. * @return [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
  408. */
  409. static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg)
  410. {
  411. return _MAV_RETURN_float(msg, 48);
  412. }
  413. /**
  414. * @brief Get field time_usec from set_home_position message
  415. *
  416. * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  417. */
  418. static inline uint64_t mavlink_msg_set_home_position_get_time_usec(const mavlink_message_t* msg)
  419. {
  420. return _MAV_RETURN_uint64_t(msg, 53);
  421. }
  422. /**
  423. * @brief Decode a set_home_position message into a struct
  424. *
  425. * @param msg The message to decode
  426. * @param set_home_position C-struct to decode the message contents into
  427. */
  428. static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position)
  429. {
  430. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  431. set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg);
  432. set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg);
  433. set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg);
  434. set_home_position->x = mavlink_msg_set_home_position_get_x(msg);
  435. set_home_position->y = mavlink_msg_set_home_position_get_y(msg);
  436. set_home_position->z = mavlink_msg_set_home_position_get_z(msg);
  437. mavlink_msg_set_home_position_get_q(msg, set_home_position->q);
  438. set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg);
  439. set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg);
  440. set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg);
  441. set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg);
  442. set_home_position->time_usec = mavlink_msg_set_home_position_get_time_usec(msg);
  443. #else
  444. uint8_t len = msg->len < MAVLINK_MSG_ID_SET_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_SET_HOME_POSITION_LEN;
  445. memset(set_home_position, 0, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  446. memcpy(set_home_position, _MAV_PAYLOAD(msg), len);
  447. #endif
  448. }