mavlink_msg_set_home_position.h 33 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558
  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
  123. * @param system_id ID of this system
  124. * @param component_id ID of this component (e.g. 200 for IMU)
  125. * @param status MAVLink status structure
  126. * @param msg The MAVLink message to compress the data into
  127. *
  128. * @param target_system System ID.
  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 World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  136. * @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.
  137. * @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.
  138. * @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.
  139. * @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.
  140. * @return length of the message in bytes (excluding serial stream start sign)
  141. */
  142. static inline uint16_t mavlink_msg_set_home_position_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  178. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
  179. #else
  180. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  181. #endif
  182. }
  183. /**
  184. * @brief Pack a set_home_position message on a channel
  185. * @param system_id ID of this system
  186. * @param component_id ID of this component (e.g. 200 for IMU)
  187. * @param chan The MAVLink channel this message will be sent over
  188. * @param msg The MAVLink message to compress the data into
  189. * @param target_system System ID.
  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 World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  197. * @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.
  198. * @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.
  199. * @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.
  200. * @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.
  201. * @return length of the message in bytes (excluding serial stream start sign)
  202. */
  203. static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  204. mavlink_message_t* msg,
  205. 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)
  206. {
  207. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  208. char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
  209. _mav_put_int32_t(buf, 0, latitude);
  210. _mav_put_int32_t(buf, 4, longitude);
  211. _mav_put_int32_t(buf, 8, altitude);
  212. _mav_put_float(buf, 12, x);
  213. _mav_put_float(buf, 16, y);
  214. _mav_put_float(buf, 20, z);
  215. _mav_put_float(buf, 40, approach_x);
  216. _mav_put_float(buf, 44, approach_y);
  217. _mav_put_float(buf, 48, approach_z);
  218. _mav_put_uint8_t(buf, 52, target_system);
  219. _mav_put_uint64_t(buf, 53, time_usec);
  220. _mav_put_float_array(buf, 24, q, 4);
  221. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  222. #else
  223. mavlink_set_home_position_t packet;
  224. packet.latitude = latitude;
  225. packet.longitude = longitude;
  226. packet.altitude = altitude;
  227. packet.x = x;
  228. packet.y = y;
  229. packet.z = z;
  230. packet.approach_x = approach_x;
  231. packet.approach_y = approach_y;
  232. packet.approach_z = approach_z;
  233. packet.target_system = target_system;
  234. packet.time_usec = time_usec;
  235. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  236. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  237. #endif
  238. msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION;
  239. 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);
  240. }
  241. /**
  242. * @brief Encode a set_home_position struct
  243. *
  244. * @param system_id ID of this system
  245. * @param component_id ID of this component (e.g. 200 for IMU)
  246. * @param msg The MAVLink message to compress the data into
  247. * @param set_home_position C-struct to read the message contents from
  248. */
  249. 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)
  250. {
  251. 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);
  252. }
  253. /**
  254. * @brief Encode a set_home_position struct on a channel
  255. *
  256. * @param system_id ID of this system
  257. * @param component_id ID of this component (e.g. 200 for IMU)
  258. * @param chan The MAVLink channel this message will be sent over
  259. * @param msg The MAVLink message to compress the data into
  260. * @param set_home_position C-struct to read the message contents from
  261. */
  262. 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)
  263. {
  264. 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);
  265. }
  266. /**
  267. * @brief Encode a set_home_position struct with provided status structure
  268. *
  269. * @param system_id ID of this system
  270. * @param component_id ID of this component (e.g. 200 for IMU)
  271. * @param status MAVLink status structure
  272. * @param msg The MAVLink message to compress the data into
  273. * @param set_home_position C-struct to read the message contents from
  274. */
  275. static inline uint16_t mavlink_msg_set_home_position_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position)
  276. {
  277. return mavlink_msg_set_home_position_pack_status(system_id, component_id, _status, 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);
  278. }
  279. /**
  280. * @brief Send a set_home_position message
  281. * @param chan MAVLink channel to send the message
  282. *
  283. * @param target_system System ID.
  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 World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  291. * @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.
  292. * @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.
  293. * @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.
  294. * @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.
  295. */
  296. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  297. 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)
  298. {
  299. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  300. char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
  301. _mav_put_int32_t(buf, 0, latitude);
  302. _mav_put_int32_t(buf, 4, longitude);
  303. _mav_put_int32_t(buf, 8, altitude);
  304. _mav_put_float(buf, 12, x);
  305. _mav_put_float(buf, 16, y);
  306. _mav_put_float(buf, 20, z);
  307. _mav_put_float(buf, 40, approach_x);
  308. _mav_put_float(buf, 44, approach_y);
  309. _mav_put_float(buf, 48, approach_z);
  310. _mav_put_uint8_t(buf, 52, target_system);
  311. _mav_put_uint64_t(buf, 53, time_usec);
  312. _mav_put_float_array(buf, 24, q, 4);
  313. _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);
  314. #else
  315. mavlink_set_home_position_t packet;
  316. packet.latitude = latitude;
  317. packet.longitude = longitude;
  318. packet.altitude = altitude;
  319. packet.x = x;
  320. packet.y = y;
  321. packet.z = z;
  322. packet.approach_x = approach_x;
  323. packet.approach_y = approach_y;
  324. packet.approach_z = approach_z;
  325. packet.target_system = target_system;
  326. packet.time_usec = time_usec;
  327. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  328. _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);
  329. #endif
  330. }
  331. /**
  332. * @brief Send a set_home_position message
  333. * @param chan MAVLink channel to send the message
  334. * @param struct The MAVLink struct to serialize
  335. */
  336. static inline void mavlink_msg_set_home_position_send_struct(mavlink_channel_t chan, const mavlink_set_home_position_t* set_home_position)
  337. {
  338. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  339. 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);
  340. #else
  341. _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);
  342. #endif
  343. }
  344. #if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  345. /*
  346. This variant of _send() can be used to save stack space by re-using
  347. memory from the receive buffer. The caller provides a
  348. mavlink_message_t which is the size of a full mavlink message. This
  349. is usually the receive buffer for the channel, and allows a reply to an
  350. incoming message with minimum stack space usage.
  351. */
  352. 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)
  353. {
  354. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  355. char *buf = (char *)msgbuf;
  356. _mav_put_int32_t(buf, 0, latitude);
  357. _mav_put_int32_t(buf, 4, longitude);
  358. _mav_put_int32_t(buf, 8, altitude);
  359. _mav_put_float(buf, 12, x);
  360. _mav_put_float(buf, 16, y);
  361. _mav_put_float(buf, 20, z);
  362. _mav_put_float(buf, 40, approach_x);
  363. _mav_put_float(buf, 44, approach_y);
  364. _mav_put_float(buf, 48, approach_z);
  365. _mav_put_uint8_t(buf, 52, target_system);
  366. _mav_put_uint64_t(buf, 53, time_usec);
  367. _mav_put_float_array(buf, 24, q, 4);
  368. _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);
  369. #else
  370. mavlink_set_home_position_t *packet = (mavlink_set_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->target_system = target_system;
  381. packet->time_usec = time_usec;
  382. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  383. _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);
  384. #endif
  385. }
  386. #endif
  387. #endif
  388. // MESSAGE SET_HOME_POSITION UNPACKING
  389. /**
  390. * @brief Get field target_system from set_home_position message
  391. *
  392. * @return System ID.
  393. */
  394. static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg)
  395. {
  396. return _MAV_RETURN_uint8_t(msg, 52);
  397. }
  398. /**
  399. * @brief Get field latitude from set_home_position message
  400. *
  401. * @return [degE7] Latitude (WGS84)
  402. */
  403. static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg)
  404. {
  405. return _MAV_RETURN_int32_t(msg, 0);
  406. }
  407. /**
  408. * @brief Get field longitude from set_home_position message
  409. *
  410. * @return [degE7] Longitude (WGS84)
  411. */
  412. static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg)
  413. {
  414. return _MAV_RETURN_int32_t(msg, 4);
  415. }
  416. /**
  417. * @brief Get field altitude from set_home_position message
  418. *
  419. * @return [mm] Altitude (MSL). Positive for up.
  420. */
  421. static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg)
  422. {
  423. return _MAV_RETURN_int32_t(msg, 8);
  424. }
  425. /**
  426. * @brief Get field x from set_home_position message
  427. *
  428. * @return [m] Local X position of this position in the local coordinate frame (NED)
  429. */
  430. static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg)
  431. {
  432. return _MAV_RETURN_float(msg, 12);
  433. }
  434. /**
  435. * @brief Get field y from set_home_position message
  436. *
  437. * @return [m] Local Y position of this position in the local coordinate frame (NED)
  438. */
  439. static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg)
  440. {
  441. return _MAV_RETURN_float(msg, 16);
  442. }
  443. /**
  444. * @brief Get field z from set_home_position message
  445. *
  446. * @return [m] Local Z position of this position in the local coordinate frame (NED: positive "down")
  447. */
  448. static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg)
  449. {
  450. return _MAV_RETURN_float(msg, 20);
  451. }
  452. /**
  453. * @brief Get field q from set_home_position message
  454. *
  455. * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
  456. */
  457. static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q)
  458. {
  459. return _MAV_RETURN_float_array(msg, q, 4, 24);
  460. }
  461. /**
  462. * @brief Get field approach_x from set_home_position message
  463. *
  464. * @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.
  465. */
  466. static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg)
  467. {
  468. return _MAV_RETURN_float(msg, 40);
  469. }
  470. /**
  471. * @brief Get field approach_y from set_home_position message
  472. *
  473. * @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.
  474. */
  475. static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg)
  476. {
  477. return _MAV_RETURN_float(msg, 44);
  478. }
  479. /**
  480. * @brief Get field approach_z from set_home_position message
  481. *
  482. * @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.
  483. */
  484. static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg)
  485. {
  486. return _MAV_RETURN_float(msg, 48);
  487. }
  488. /**
  489. * @brief Get field time_usec from set_home_position message
  490. *
  491. * @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.
  492. */
  493. static inline uint64_t mavlink_msg_set_home_position_get_time_usec(const mavlink_message_t* msg)
  494. {
  495. return _MAV_RETURN_uint64_t(msg, 53);
  496. }
  497. /**
  498. * @brief Decode a set_home_position message into a struct
  499. *
  500. * @param msg The message to decode
  501. * @param set_home_position C-struct to decode the message contents into
  502. */
  503. static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position)
  504. {
  505. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  506. set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg);
  507. set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg);
  508. set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg);
  509. set_home_position->x = mavlink_msg_set_home_position_get_x(msg);
  510. set_home_position->y = mavlink_msg_set_home_position_get_y(msg);
  511. set_home_position->z = mavlink_msg_set_home_position_get_z(msg);
  512. mavlink_msg_set_home_position_get_q(msg, set_home_position->q);
  513. set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg);
  514. set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg);
  515. set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg);
  516. set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg);
  517. set_home_position->time_usec = mavlink_msg_set_home_position_get_time_usec(msg);
  518. #else
  519. uint8_t len = msg->len < MAVLINK_MSG_ID_SET_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_SET_HOME_POSITION_LEN;
  520. memset(set_home_position, 0, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
  521. memcpy(set_home_position, _MAV_PAYLOAD(msg), len);
  522. #endif
  523. }