[324] | 1 | // MESSAGE HOME_POSITION PACKING
|
---|
| 2 |
|
---|
| 3 | #define MAVLINK_MSG_ID_HOME_POSITION 242
|
---|
| 4 |
|
---|
| 5 | typedef struct MAVLINK_PACKED __mavlink_home_position_t
|
---|
| 6 | {
|
---|
| 7 | int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/
|
---|
| 8 | int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/
|
---|
| 9 | int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/
|
---|
| 10 | float x; /*< Local X position of this position in the local coordinate frame*/
|
---|
| 11 | float y; /*< Local Y position of this position in the local coordinate frame*/
|
---|
| 12 | float z; /*< Local Z position of this position in the local coordinate frame*/
|
---|
| 13 | float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/
|
---|
| 14 | float approach_x; /*< 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.*/
|
---|
| 15 | float approach_y; /*< 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.*/
|
---|
| 16 | float approach_z; /*< 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.*/
|
---|
| 17 | } mavlink_home_position_t;
|
---|
| 18 |
|
---|
| 19 | #define MAVLINK_MSG_ID_HOME_POSITION_LEN 52
|
---|
| 20 | #define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52
|
---|
| 21 | #define MAVLINK_MSG_ID_242_LEN 52
|
---|
| 22 | #define MAVLINK_MSG_ID_242_MIN_LEN 52
|
---|
| 23 |
|
---|
| 24 | #define MAVLINK_MSG_ID_HOME_POSITION_CRC 104
|
---|
| 25 | #define MAVLINK_MSG_ID_242_CRC 104
|
---|
| 26 |
|
---|
| 27 | #define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4
|
---|
| 28 |
|
---|
| 29 | #if MAVLINK_COMMAND_24BIT
|
---|
| 30 | #define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
|
---|
| 31 | 242, \
|
---|
| 32 | "HOME_POSITION", \
|
---|
| 33 | 10, \
|
---|
| 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 | } \
|
---|
| 45 | }
|
---|
| 46 | #else
|
---|
| 47 | #define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
|
---|
| 48 | "HOME_POSITION", \
|
---|
| 49 | 10, \
|
---|
| 50 | { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \
|
---|
| 51 | { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \
|
---|
| 52 | { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \
|
---|
| 53 | { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \
|
---|
| 54 | { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \
|
---|
| 55 | { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \
|
---|
| 56 | { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \
|
---|
| 57 | { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \
|
---|
| 58 | { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \
|
---|
| 59 | { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \
|
---|
| 60 | } \
|
---|
| 61 | }
|
---|
| 62 | #endif
|
---|
| 63 |
|
---|
| 64 | /**
|
---|
| 65 | * @brief Pack a 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 latitude Latitude (WGS84), in degrees * 1E7
|
---|
| 71 | * @param longitude Longitude (WGS84, in degrees * 1E7
|
---|
| 72 | * @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
|
---|
| 73 | * @param x Local X position of this position in the local coordinate frame
|
---|
| 74 | * @param y Local Y position of this position in the local coordinate frame
|
---|
| 75 | * @param z Local Z position of this position in the local coordinate frame
|
---|
| 76 | * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
|
---|
| 77 | * @param approach_x 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.
|
---|
| 78 | * @param approach_y 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.
|
---|
| 79 | * @param approach_z 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.
|
---|
| 80 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 81 | */
|
---|
| 82 | static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
| 83 | 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)
|
---|
| 84 | {
|
---|
| 85 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 86 | char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
|
---|
| 87 | _mav_put_int32_t(buf, 0, latitude);
|
---|
| 88 | _mav_put_int32_t(buf, 4, longitude);
|
---|
| 89 | _mav_put_int32_t(buf, 8, altitude);
|
---|
| 90 | _mav_put_float(buf, 12, x);
|
---|
| 91 | _mav_put_float(buf, 16, y);
|
---|
| 92 | _mav_put_float(buf, 20, z);
|
---|
| 93 | _mav_put_float(buf, 40, approach_x);
|
---|
| 94 | _mav_put_float(buf, 44, approach_y);
|
---|
| 95 | _mav_put_float(buf, 48, approach_z);
|
---|
| 96 | _mav_put_float_array(buf, 24, q, 4);
|
---|
| 97 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
|
---|
| 98 | #else
|
---|
| 99 | mavlink_home_position_t packet;
|
---|
| 100 | packet.latitude = latitude;
|
---|
| 101 | packet.longitude = longitude;
|
---|
| 102 | packet.altitude = altitude;
|
---|
| 103 | packet.x = x;
|
---|
| 104 | packet.y = y;
|
---|
| 105 | packet.z = z;
|
---|
| 106 | packet.approach_x = approach_x;
|
---|
| 107 | packet.approach_y = approach_y;
|
---|
| 108 | packet.approach_z = approach_z;
|
---|
| 109 | mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
---|
| 110 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
|
---|
| 111 | #endif
|
---|
| 112 |
|
---|
| 113 | msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
|
---|
| 114 | 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);
|
---|
| 115 | }
|
---|
| 116 |
|
---|
| 117 | /**
|
---|
| 118 | * @brief Pack a home_position message on a channel
|
---|
| 119 | * @param system_id ID of this system
|
---|
| 120 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 121 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 122 | * @param msg The MAVLink message to compress the data into
|
---|
| 123 | * @param latitude Latitude (WGS84), in degrees * 1E7
|
---|
| 124 | * @param longitude Longitude (WGS84, in degrees * 1E7
|
---|
| 125 | * @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
|
---|
| 126 | * @param x Local X position of this position in the local coordinate frame
|
---|
| 127 | * @param y Local Y position of this position in the local coordinate frame
|
---|
| 128 | * @param z Local Z position of this position in the local coordinate frame
|
---|
| 129 | * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
|
---|
| 130 | * @param approach_x 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.
|
---|
| 131 | * @param approach_y 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.
|
---|
| 132 | * @param approach_z 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.
|
---|
| 133 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 134 | */
|
---|
| 135 | static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
| 136 | mavlink_message_t* msg,
|
---|
| 137 | 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)
|
---|
| 138 | {
|
---|
| 139 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 140 | char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
|
---|
| 141 | _mav_put_int32_t(buf, 0, latitude);
|
---|
| 142 | _mav_put_int32_t(buf, 4, longitude);
|
---|
| 143 | _mav_put_int32_t(buf, 8, altitude);
|
---|
| 144 | _mav_put_float(buf, 12, x);
|
---|
| 145 | _mav_put_float(buf, 16, y);
|
---|
| 146 | _mav_put_float(buf, 20, z);
|
---|
| 147 | _mav_put_float(buf, 40, approach_x);
|
---|
| 148 | _mav_put_float(buf, 44, approach_y);
|
---|
| 149 | _mav_put_float(buf, 48, approach_z);
|
---|
| 150 | _mav_put_float_array(buf, 24, q, 4);
|
---|
| 151 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
|
---|
| 152 | #else
|
---|
| 153 | mavlink_home_position_t packet;
|
---|
| 154 | packet.latitude = latitude;
|
---|
| 155 | packet.longitude = longitude;
|
---|
| 156 | packet.altitude = altitude;
|
---|
| 157 | packet.x = x;
|
---|
| 158 | packet.y = y;
|
---|
| 159 | packet.z = z;
|
---|
| 160 | packet.approach_x = approach_x;
|
---|
| 161 | packet.approach_y = approach_y;
|
---|
| 162 | packet.approach_z = approach_z;
|
---|
| 163 | mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
---|
| 164 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
|
---|
| 165 | #endif
|
---|
| 166 |
|
---|
| 167 | msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
|
---|
| 168 | 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);
|
---|
| 169 | }
|
---|
| 170 |
|
---|
| 171 | /**
|
---|
| 172 | * @brief Encode a home_position struct
|
---|
| 173 | *
|
---|
| 174 | * @param system_id ID of this system
|
---|
| 175 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 176 | * @param msg The MAVLink message to compress the data into
|
---|
| 177 | * @param home_position C-struct to read the message contents from
|
---|
| 178 | */
|
---|
| 179 | 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)
|
---|
| 180 | {
|
---|
| 181 | 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);
|
---|
| 182 | }
|
---|
| 183 |
|
---|
| 184 | /**
|
---|
| 185 | * @brief Encode a home_position struct on a channel
|
---|
| 186 | *
|
---|
| 187 | * @param system_id ID of this system
|
---|
| 188 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 189 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 190 | * @param msg The MAVLink message to compress the data into
|
---|
| 191 | * @param home_position C-struct to read the message contents from
|
---|
| 192 | */
|
---|
| 193 | 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)
|
---|
| 194 | {
|
---|
| 195 | 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);
|
---|
| 196 | }
|
---|
| 197 |
|
---|
| 198 | /**
|
---|
| 199 | * @brief Send a home_position message
|
---|
| 200 | * @param chan MAVLink channel to send the message
|
---|
| 201 | *
|
---|
| 202 | * @param latitude Latitude (WGS84), in degrees * 1E7
|
---|
| 203 | * @param longitude Longitude (WGS84, in degrees * 1E7
|
---|
| 204 | * @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
|
---|
| 205 | * @param x Local X position of this position in the local coordinate frame
|
---|
| 206 | * @param y Local Y position of this position in the local coordinate frame
|
---|
| 207 | * @param z Local Z position of this position in the local coordinate frame
|
---|
| 208 | * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
|
---|
| 209 | * @param approach_x 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.
|
---|
| 210 | * @param approach_y 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.
|
---|
| 211 | * @param approach_z 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.
|
---|
| 212 | */
|
---|
| 213 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
| 214 |
|
---|
| 215 | 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)
|
---|
| 216 | {
|
---|
| 217 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 218 | char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
|
---|
| 219 | _mav_put_int32_t(buf, 0, latitude);
|
---|
| 220 | _mav_put_int32_t(buf, 4, longitude);
|
---|
| 221 | _mav_put_int32_t(buf, 8, altitude);
|
---|
| 222 | _mav_put_float(buf, 12, x);
|
---|
| 223 | _mav_put_float(buf, 16, y);
|
---|
| 224 | _mav_put_float(buf, 20, z);
|
---|
| 225 | _mav_put_float(buf, 40, approach_x);
|
---|
| 226 | _mav_put_float(buf, 44, approach_y);
|
---|
| 227 | _mav_put_float(buf, 48, approach_z);
|
---|
| 228 | _mav_put_float_array(buf, 24, q, 4);
|
---|
| 229 | _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);
|
---|
| 230 | #else
|
---|
| 231 | mavlink_home_position_t packet;
|
---|
| 232 | packet.latitude = latitude;
|
---|
| 233 | packet.longitude = longitude;
|
---|
| 234 | packet.altitude = altitude;
|
---|
| 235 | packet.x = x;
|
---|
| 236 | packet.y = y;
|
---|
| 237 | packet.z = z;
|
---|
| 238 | packet.approach_x = approach_x;
|
---|
| 239 | packet.approach_y = approach_y;
|
---|
| 240 | packet.approach_z = approach_z;
|
---|
| 241 | mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
---|
| 242 | _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);
|
---|
| 243 | #endif
|
---|
| 244 | }
|
---|
| 245 |
|
---|
| 246 | /**
|
---|
| 247 | * @brief Send a home_position message
|
---|
| 248 | * @param chan MAVLink channel to send the message
|
---|
| 249 | * @param struct The MAVLink struct to serialize
|
---|
| 250 | */
|
---|
| 251 | static inline void mavlink_msg_home_position_send_struct(mavlink_channel_t chan, const mavlink_home_position_t* home_position)
|
---|
| 252 | {
|
---|
| 253 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 254 | 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);
|
---|
| 255 | #else
|
---|
| 256 | _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);
|
---|
| 257 | #endif
|
---|
| 258 | }
|
---|
| 259 |
|
---|
| 260 | #if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
| 261 | /*
|
---|
| 262 | This varient of _send() can be used to save stack space by re-using
|
---|
| 263 | memory from the receive buffer. The caller provides a
|
---|
| 264 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
| 265 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
| 266 | incoming message with minimum stack space usage.
|
---|
| 267 | */
|
---|
| 268 | 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)
|
---|
| 269 | {
|
---|
| 270 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 271 | char *buf = (char *)msgbuf;
|
---|
| 272 | _mav_put_int32_t(buf, 0, latitude);
|
---|
| 273 | _mav_put_int32_t(buf, 4, longitude);
|
---|
| 274 | _mav_put_int32_t(buf, 8, altitude);
|
---|
| 275 | _mav_put_float(buf, 12, x);
|
---|
| 276 | _mav_put_float(buf, 16, y);
|
---|
| 277 | _mav_put_float(buf, 20, z);
|
---|
| 278 | _mav_put_float(buf, 40, approach_x);
|
---|
| 279 | _mav_put_float(buf, 44, approach_y);
|
---|
| 280 | _mav_put_float(buf, 48, approach_z);
|
---|
| 281 | _mav_put_float_array(buf, 24, q, 4);
|
---|
| 282 | _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);
|
---|
| 283 | #else
|
---|
| 284 | mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf;
|
---|
| 285 | packet->latitude = latitude;
|
---|
| 286 | packet->longitude = longitude;
|
---|
| 287 | packet->altitude = altitude;
|
---|
| 288 | packet->x = x;
|
---|
| 289 | packet->y = y;
|
---|
| 290 | packet->z = z;
|
---|
| 291 | packet->approach_x = approach_x;
|
---|
| 292 | packet->approach_y = approach_y;
|
---|
| 293 | packet->approach_z = approach_z;
|
---|
| 294 | mav_array_memcpy(packet->q, q, sizeof(float)*4);
|
---|
| 295 | _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);
|
---|
| 296 | #endif
|
---|
| 297 | }
|
---|
| 298 | #endif
|
---|
| 299 |
|
---|
| 300 | #endif
|
---|
| 301 |
|
---|
| 302 | // MESSAGE HOME_POSITION UNPACKING
|
---|
| 303 |
|
---|
| 304 |
|
---|
| 305 | /**
|
---|
| 306 | * @brief Get field latitude from home_position message
|
---|
| 307 | *
|
---|
| 308 | * @return Latitude (WGS84), in degrees * 1E7
|
---|
| 309 | */
|
---|
| 310 | static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg)
|
---|
| 311 | {
|
---|
| 312 | return _MAV_RETURN_int32_t(msg, 0);
|
---|
| 313 | }
|
---|
| 314 |
|
---|
| 315 | /**
|
---|
| 316 | * @brief Get field longitude from home_position message
|
---|
| 317 | *
|
---|
| 318 | * @return Longitude (WGS84, in degrees * 1E7
|
---|
| 319 | */
|
---|
| 320 | static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg)
|
---|
| 321 | {
|
---|
| 322 | return _MAV_RETURN_int32_t(msg, 4);
|
---|
| 323 | }
|
---|
| 324 |
|
---|
| 325 | /**
|
---|
| 326 | * @brief Get field altitude from home_position message
|
---|
| 327 | *
|
---|
| 328 | * @return Altitude (AMSL), in meters * 1000 (positive for up)
|
---|
| 329 | */
|
---|
| 330 | static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg)
|
---|
| 331 | {
|
---|
| 332 | return _MAV_RETURN_int32_t(msg, 8);
|
---|
| 333 | }
|
---|
| 334 |
|
---|
| 335 | /**
|
---|
| 336 | * @brief Get field x from home_position message
|
---|
| 337 | *
|
---|
| 338 | * @return Local X position of this position in the local coordinate frame
|
---|
| 339 | */
|
---|
| 340 | static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg)
|
---|
| 341 | {
|
---|
| 342 | return _MAV_RETURN_float(msg, 12);
|
---|
| 343 | }
|
---|
| 344 |
|
---|
| 345 | /**
|
---|
| 346 | * @brief Get field y from home_position message
|
---|
| 347 | *
|
---|
| 348 | * @return Local Y position of this position in the local coordinate frame
|
---|
| 349 | */
|
---|
| 350 | static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg)
|
---|
| 351 | {
|
---|
| 352 | return _MAV_RETURN_float(msg, 16);
|
---|
| 353 | }
|
---|
| 354 |
|
---|
| 355 | /**
|
---|
| 356 | * @brief Get field z from home_position message
|
---|
| 357 | *
|
---|
| 358 | * @return Local Z position of this position in the local coordinate frame
|
---|
| 359 | */
|
---|
| 360 | static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg)
|
---|
| 361 | {
|
---|
| 362 | return _MAV_RETURN_float(msg, 20);
|
---|
| 363 | }
|
---|
| 364 |
|
---|
| 365 | /**
|
---|
| 366 | * @brief Get field q from home_position message
|
---|
| 367 | *
|
---|
| 368 | * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
|
---|
| 369 | */
|
---|
| 370 | static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q)
|
---|
| 371 | {
|
---|
| 372 | return _MAV_RETURN_float_array(msg, q, 4, 24);
|
---|
| 373 | }
|
---|
| 374 |
|
---|
| 375 | /**
|
---|
| 376 | * @brief Get field approach_x from home_position message
|
---|
| 377 | *
|
---|
| 378 | * @return 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.
|
---|
| 379 | */
|
---|
| 380 | static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg)
|
---|
| 381 | {
|
---|
| 382 | return _MAV_RETURN_float(msg, 40);
|
---|
| 383 | }
|
---|
| 384 |
|
---|
| 385 | /**
|
---|
| 386 | * @brief Get field approach_y from home_position message
|
---|
| 387 | *
|
---|
| 388 | * @return 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.
|
---|
| 389 | */
|
---|
| 390 | static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg)
|
---|
| 391 | {
|
---|
| 392 | return _MAV_RETURN_float(msg, 44);
|
---|
| 393 | }
|
---|
| 394 |
|
---|
| 395 | /**
|
---|
| 396 | * @brief Get field approach_z from home_position message
|
---|
| 397 | *
|
---|
| 398 | * @return 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.
|
---|
| 399 | */
|
---|
| 400 | static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg)
|
---|
| 401 | {
|
---|
| 402 | return _MAV_RETURN_float(msg, 48);
|
---|
| 403 | }
|
---|
| 404 |
|
---|
| 405 | /**
|
---|
| 406 | * @brief Decode a home_position message into a struct
|
---|
| 407 | *
|
---|
| 408 | * @param msg The message to decode
|
---|
| 409 | * @param home_position C-struct to decode the message contents into
|
---|
| 410 | */
|
---|
| 411 | static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position)
|
---|
| 412 | {
|
---|
| 413 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 414 | home_position->latitude = mavlink_msg_home_position_get_latitude(msg);
|
---|
| 415 | home_position->longitude = mavlink_msg_home_position_get_longitude(msg);
|
---|
| 416 | home_position->altitude = mavlink_msg_home_position_get_altitude(msg);
|
---|
| 417 | home_position->x = mavlink_msg_home_position_get_x(msg);
|
---|
| 418 | home_position->y = mavlink_msg_home_position_get_y(msg);
|
---|
| 419 | home_position->z = mavlink_msg_home_position_get_z(msg);
|
---|
| 420 | mavlink_msg_home_position_get_q(msg, home_position->q);
|
---|
| 421 | home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg);
|
---|
| 422 | home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg);
|
---|
| 423 | home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg);
|
---|
| 424 | #else
|
---|
| 425 | uint8_t len = msg->len < MAVLINK_MSG_ID_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_HOME_POSITION_LEN;
|
---|
| 426 | memset(home_position, 0, MAVLINK_MSG_ID_HOME_POSITION_LEN);
|
---|
| 427 | memcpy(home_position, _MAV_PAYLOAD(msg), len);
|
---|
| 428 | #endif
|
---|
| 429 | }
|
---|