mavlink_msg_home_position.h 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554
  1. #pragma once
  2. // MESSAGE HOME_POSITION PACKING
  3. #define MAVLINK_MSG_ID_HOME_POSITION 242
  4. MAVPACKED(
  5. typedef struct __mavlink_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]; /*<
  13. Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position.
  14. Used to indicate the heading and slope of the ground.
  15. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied.
  16. */
  17. 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.*/
  18. 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.*/
  19. 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.*/
  20. 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.*/
  21. }) mavlink_home_position_t;
  22. #define MAVLINK_MSG_ID_HOME_POSITION_LEN 60
  23. #define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52
  24. #define MAVLINK_MSG_ID_242_LEN 60
  25. #define MAVLINK_MSG_ID_242_MIN_LEN 52
  26. #define MAVLINK_MSG_ID_HOME_POSITION_CRC 104
  27. #define MAVLINK_MSG_ID_242_CRC 104
  28. #define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4
  29. #if MAVLINK_COMMAND_24BIT
  30. #define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
  31. 242, \
  32. "HOME_POSITION", \
  33. 11, \
  34. { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \
  35. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \
  36. { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \
  37. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \
  38. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \
  39. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \
  40. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \
  41. { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \
  42. { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \
  43. { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \
  44. { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 52, offsetof(mavlink_home_position_t, time_usec) }, \
  45. } \
  46. }
  47. #else
  48. #define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
  49. "HOME_POSITION", \
  50. 11, \
  51. { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \
  52. { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \
  53. { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \
  54. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \
  55. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \
  56. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \
  57. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \
  58. { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \
  59. { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \
  60. { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \
  61. { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 52, offsetof(mavlink_home_position_t, time_usec) }, \
  62. } \
  63. }
  64. #endif
  65. /**
  66. * @brief Pack a home_position message
  67. * @param system_id ID of this system
  68. * @param component_id ID of this component (e.g. 200 for IMU)
  69. * @param msg The MAVLink message to compress the data into
  70. *
  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
  78. Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position.
  79. Used to indicate the heading and slope of the ground.
  80. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied.
  81. * @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.
  82. * @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.
  83. * @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.
  84. * @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.
  85. * @return length of the message in bytes (excluding serial stream start sign)
  86. */
  87. static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  88. 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)
  89. {
  90. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  91. char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
  92. _mav_put_int32_t(buf, 0, latitude);
  93. _mav_put_int32_t(buf, 4, longitude);
  94. _mav_put_int32_t(buf, 8, altitude);
  95. _mav_put_float(buf, 12, x);
  96. _mav_put_float(buf, 16, y);
  97. _mav_put_float(buf, 20, z);
  98. _mav_put_float(buf, 40, approach_x);
  99. _mav_put_float(buf, 44, approach_y);
  100. _mav_put_float(buf, 48, approach_z);
  101. _mav_put_uint64_t(buf, 52, time_usec);
  102. _mav_put_float_array(buf, 24, q, 4);
  103. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  104. #else
  105. mavlink_home_position_t packet;
  106. packet.latitude = latitude;
  107. packet.longitude = longitude;
  108. packet.altitude = altitude;
  109. packet.x = x;
  110. packet.y = y;
  111. packet.z = z;
  112. packet.approach_x = approach_x;
  113. packet.approach_y = approach_y;
  114. packet.approach_z = approach_z;
  115. packet.time_usec = time_usec;
  116. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  117. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  118. #endif
  119. msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
  120. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  121. }
  122. /**
  123. * @brief Pack a home_position message
  124. * @param system_id ID of this system
  125. * @param component_id ID of this component (e.g. 200 for IMU)
  126. * @param status MAVLink status structure
  127. * @param msg The MAVLink message to compress the data into
  128. *
  129. * @param latitude [degE7] Latitude (WGS84)
  130. * @param longitude [degE7] Longitude (WGS84)
  131. * @param altitude [mm] Altitude (MSL). Positive for up.
  132. * @param x [m] Local X position of this position in the local coordinate frame (NED)
  133. * @param y [m] Local Y position of this position in the local coordinate frame (NED)
  134. * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  135. * @param q
  136. Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position.
  137. Used to indicate the heading and slope of the ground.
  138. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied.
  139. * @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.
  140. * @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.
  141. * @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.
  142. * @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.
  143. * @return length of the message in bytes (excluding serial stream start sign)
  144. */
  145. static inline uint16_t mavlink_msg_home_position_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  146. 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)
  147. {
  148. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  149. char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
  150. _mav_put_int32_t(buf, 0, latitude);
  151. _mav_put_int32_t(buf, 4, longitude);
  152. _mav_put_int32_t(buf, 8, altitude);
  153. _mav_put_float(buf, 12, x);
  154. _mav_put_float(buf, 16, y);
  155. _mav_put_float(buf, 20, z);
  156. _mav_put_float(buf, 40, approach_x);
  157. _mav_put_float(buf, 44, approach_y);
  158. _mav_put_float(buf, 48, approach_z);
  159. _mav_put_uint64_t(buf, 52, time_usec);
  160. _mav_put_float_array(buf, 24, q, 4);
  161. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  162. #else
  163. mavlink_home_position_t packet;
  164. packet.latitude = latitude;
  165. packet.longitude = longitude;
  166. packet.altitude = altitude;
  167. packet.x = x;
  168. packet.y = y;
  169. packet.z = z;
  170. packet.approach_x = approach_x;
  171. packet.approach_y = approach_y;
  172. packet.approach_z = approach_z;
  173. packet.time_usec = time_usec;
  174. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  175. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  176. #endif
  177. msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
  178. #if MAVLINK_CRC_EXTRA
  179. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  180. #else
  181. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  182. #endif
  183. }
  184. /**
  185. * @brief Pack a home_position message on a channel
  186. * @param system_id ID of this system
  187. * @param component_id ID of this component (e.g. 200 for IMU)
  188. * @param chan The MAVLink channel this message will be sent over
  189. * @param msg The MAVLink message to compress the data into
  190. * @param latitude [degE7] Latitude (WGS84)
  191. * @param longitude [degE7] Longitude (WGS84)
  192. * @param altitude [mm] Altitude (MSL). Positive for up.
  193. * @param x [m] Local X position of this position in the local coordinate frame (NED)
  194. * @param y [m] Local Y position of this position in the local coordinate frame (NED)
  195. * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  196. * @param q
  197. Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position.
  198. Used to indicate the heading and slope of the ground.
  199. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied.
  200. * @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.
  201. * @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.
  202. * @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.
  203. * @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.
  204. * @return length of the message in bytes (excluding serial stream start sign)
  205. */
  206. static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  207. mavlink_message_t* msg,
  208. 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)
  209. {
  210. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  211. char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
  212. _mav_put_int32_t(buf, 0, latitude);
  213. _mav_put_int32_t(buf, 4, longitude);
  214. _mav_put_int32_t(buf, 8, altitude);
  215. _mav_put_float(buf, 12, x);
  216. _mav_put_float(buf, 16, y);
  217. _mav_put_float(buf, 20, z);
  218. _mav_put_float(buf, 40, approach_x);
  219. _mav_put_float(buf, 44, approach_y);
  220. _mav_put_float(buf, 48, approach_z);
  221. _mav_put_uint64_t(buf, 52, time_usec);
  222. _mav_put_float_array(buf, 24, q, 4);
  223. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  224. #else
  225. mavlink_home_position_t packet;
  226. packet.latitude = latitude;
  227. packet.longitude = longitude;
  228. packet.altitude = altitude;
  229. packet.x = x;
  230. packet.y = y;
  231. packet.z = z;
  232. packet.approach_x = approach_x;
  233. packet.approach_y = approach_y;
  234. packet.approach_z = approach_z;
  235. packet.time_usec = time_usec;
  236. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  237. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  238. #endif
  239. msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
  240. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  241. }
  242. /**
  243. * @brief Encode a home_position struct
  244. *
  245. * @param system_id ID of this system
  246. * @param component_id ID of this component (e.g. 200 for IMU)
  247. * @param msg The MAVLink message to compress the data into
  248. * @param home_position C-struct to read the message contents from
  249. */
  250. static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_home_position_t* home_position)
  251. {
  252. return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec);
  253. }
  254. /**
  255. * @brief Encode a home_position struct on a channel
  256. *
  257. * @param system_id ID of this system
  258. * @param component_id ID of this component (e.g. 200 for IMU)
  259. * @param chan The MAVLink channel this message will be sent over
  260. * @param msg The MAVLink message to compress the data into
  261. * @param home_position C-struct to read the message contents from
  262. */
  263. static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_home_position_t* home_position)
  264. {
  265. return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec);
  266. }
  267. /**
  268. * @brief Encode a home_position struct with provided status structure
  269. *
  270. * @param system_id ID of this system
  271. * @param component_id ID of this component (e.g. 200 for IMU)
  272. * @param status MAVLink status structure
  273. * @param msg The MAVLink message to compress the data into
  274. * @param home_position C-struct to read the message contents from
  275. */
  276. static inline uint16_t mavlink_msg_home_position_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_home_position_t* home_position)
  277. {
  278. return mavlink_msg_home_position_pack_status(system_id, component_id, _status, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec);
  279. }
  280. /**
  281. * @brief Send a home_position message
  282. * @param chan MAVLink channel to send the message
  283. *
  284. * @param latitude [degE7] Latitude (WGS84)
  285. * @param longitude [degE7] Longitude (WGS84)
  286. * @param altitude [mm] Altitude (MSL). Positive for up.
  287. * @param x [m] Local X position of this position in the local coordinate frame (NED)
  288. * @param y [m] Local Y position of this position in the local coordinate frame (NED)
  289. * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  290. * @param q
  291. Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position.
  292. Used to indicate the heading and slope of the ground.
  293. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied.
  294. * @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.
  295. * @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.
  296. * @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.
  297. * @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.
  298. */
  299. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  300. static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, 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)
  301. {
  302. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  303. char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
  304. _mav_put_int32_t(buf, 0, latitude);
  305. _mav_put_int32_t(buf, 4, longitude);
  306. _mav_put_int32_t(buf, 8, altitude);
  307. _mav_put_float(buf, 12, x);
  308. _mav_put_float(buf, 16, y);
  309. _mav_put_float(buf, 20, z);
  310. _mav_put_float(buf, 40, approach_x);
  311. _mav_put_float(buf, 44, approach_y);
  312. _mav_put_float(buf, 48, approach_z);
  313. _mav_put_uint64_t(buf, 52, time_usec);
  314. _mav_put_float_array(buf, 24, q, 4);
  315. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  316. #else
  317. mavlink_home_position_t packet;
  318. packet.latitude = latitude;
  319. packet.longitude = longitude;
  320. packet.altitude = altitude;
  321. packet.x = x;
  322. packet.y = y;
  323. packet.z = z;
  324. packet.approach_x = approach_x;
  325. packet.approach_y = approach_y;
  326. packet.approach_z = approach_z;
  327. packet.time_usec = time_usec;
  328. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  329. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  330. #endif
  331. }
  332. /**
  333. * @brief Send a home_position message
  334. * @param chan MAVLink channel to send the message
  335. * @param struct The MAVLink struct to serialize
  336. */
  337. static inline void mavlink_msg_home_position_send_struct(mavlink_channel_t chan, const mavlink_home_position_t* home_position)
  338. {
  339. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  340. mavlink_msg_home_position_send(chan, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec);
  341. #else
  342. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)home_position, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  343. #endif
  344. }
  345. #if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  346. /*
  347. This variant of _send() can be used to save stack space by re-using
  348. memory from the receive buffer. The caller provides a
  349. mavlink_message_t which is the size of a full mavlink message. This
  350. is usually the receive buffer for the channel, and allows a reply to an
  351. incoming message with minimum stack space usage.
  352. */
  353. static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, 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)
  354. {
  355. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  356. char *buf = (char *)msgbuf;
  357. _mav_put_int32_t(buf, 0, latitude);
  358. _mav_put_int32_t(buf, 4, longitude);
  359. _mav_put_int32_t(buf, 8, altitude);
  360. _mav_put_float(buf, 12, x);
  361. _mav_put_float(buf, 16, y);
  362. _mav_put_float(buf, 20, z);
  363. _mav_put_float(buf, 40, approach_x);
  364. _mav_put_float(buf, 44, approach_y);
  365. _mav_put_float(buf, 48, approach_z);
  366. _mav_put_uint64_t(buf, 52, time_usec);
  367. _mav_put_float_array(buf, 24, q, 4);
  368. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  369. #else
  370. mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf;
  371. packet->latitude = latitude;
  372. packet->longitude = longitude;
  373. packet->altitude = altitude;
  374. packet->x = x;
  375. packet->y = y;
  376. packet->z = z;
  377. packet->approach_x = approach_x;
  378. packet->approach_y = approach_y;
  379. packet->approach_z = approach_z;
  380. packet->time_usec = time_usec;
  381. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  382. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
  383. #endif
  384. }
  385. #endif
  386. #endif
  387. // MESSAGE HOME_POSITION UNPACKING
  388. /**
  389. * @brief Get field latitude from home_position message
  390. *
  391. * @return [degE7] Latitude (WGS84)
  392. */
  393. static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg)
  394. {
  395. return _MAV_RETURN_int32_t(msg, 0);
  396. }
  397. /**
  398. * @brief Get field longitude from home_position message
  399. *
  400. * @return [degE7] Longitude (WGS84)
  401. */
  402. static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg)
  403. {
  404. return _MAV_RETURN_int32_t(msg, 4);
  405. }
  406. /**
  407. * @brief Get field altitude from home_position message
  408. *
  409. * @return [mm] Altitude (MSL). Positive for up.
  410. */
  411. static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg)
  412. {
  413. return _MAV_RETURN_int32_t(msg, 8);
  414. }
  415. /**
  416. * @brief Get field x from home_position message
  417. *
  418. * @return [m] Local X position of this position in the local coordinate frame (NED)
  419. */
  420. static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg)
  421. {
  422. return _MAV_RETURN_float(msg, 12);
  423. }
  424. /**
  425. * @brief Get field y from home_position message
  426. *
  427. * @return [m] Local Y position of this position in the local coordinate frame (NED)
  428. */
  429. static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg)
  430. {
  431. return _MAV_RETURN_float(msg, 16);
  432. }
  433. /**
  434. * @brief Get field z from home_position message
  435. *
  436. * @return [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  437. */
  438. static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg)
  439. {
  440. return _MAV_RETURN_float(msg, 20);
  441. }
  442. /**
  443. * @brief Get field q from home_position message
  444. *
  445. * @return
  446. Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position.
  447. Used to indicate the heading and slope of the ground.
  448. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied.
  449. */
  450. static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q)
  451. {
  452. return _MAV_RETURN_float_array(msg, q, 4, 24);
  453. }
  454. /**
  455. * @brief Get field approach_x from home_position message
  456. *
  457. * @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.
  458. */
  459. static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg)
  460. {
  461. return _MAV_RETURN_float(msg, 40);
  462. }
  463. /**
  464. * @brief Get field approach_y from home_position message
  465. *
  466. * @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.
  467. */
  468. static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg)
  469. {
  470. return _MAV_RETURN_float(msg, 44);
  471. }
  472. /**
  473. * @brief Get field approach_z from home_position message
  474. *
  475. * @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.
  476. */
  477. static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg)
  478. {
  479. return _MAV_RETURN_float(msg, 48);
  480. }
  481. /**
  482. * @brief Get field time_usec from home_position message
  483. *
  484. * @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.
  485. */
  486. static inline uint64_t mavlink_msg_home_position_get_time_usec(const mavlink_message_t* msg)
  487. {
  488. return _MAV_RETURN_uint64_t(msg, 52);
  489. }
  490. /**
  491. * @brief Decode a home_position message into a struct
  492. *
  493. * @param msg The message to decode
  494. * @param home_position C-struct to decode the message contents into
  495. */
  496. static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position)
  497. {
  498. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  499. home_position->latitude = mavlink_msg_home_position_get_latitude(msg);
  500. home_position->longitude = mavlink_msg_home_position_get_longitude(msg);
  501. home_position->altitude = mavlink_msg_home_position_get_altitude(msg);
  502. home_position->x = mavlink_msg_home_position_get_x(msg);
  503. home_position->y = mavlink_msg_home_position_get_y(msg);
  504. home_position->z = mavlink_msg_home_position_get_z(msg);
  505. mavlink_msg_home_position_get_q(msg, home_position->q);
  506. home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg);
  507. home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg);
  508. home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg);
  509. home_position->time_usec = mavlink_msg_home_position_get_time_usec(msg);
  510. #else
  511. uint8_t len = msg->len < MAVLINK_MSG_ID_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_HOME_POSITION_LEN;
  512. memset(home_position, 0, MAVLINK_MSG_ID_HOME_POSITION_LEN);
  513. memcpy(home_position, _MAV_PAYLOAD(msg), len);
  514. #endif
  515. }