mavlink_msg_home_position.h
Go to the documentation of this file.
00001 // MESSAGE HOME_POSITION PACKING
00002 
00003 #define MAVLINK_MSG_ID_HOME_POSITION 242
00004 
00005 typedef struct __mavlink_home_position_t
00006 {
00007  int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/
00008  int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/
00009  int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/
00010  float x; /*< Local X position of this position in the local coordinate frame*/
00011  float y; /*< Local Y position of this position in the local coordinate frame*/
00012  float z; /*< Local Z position of this position in the local coordinate frame*/
00013  float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/
00014  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.*/
00015  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.*/
00016  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.*/
00017 } mavlink_home_position_t;
00018 
00019 #define MAVLINK_MSG_ID_HOME_POSITION_LEN 52
00020 #define MAVLINK_MSG_ID_242_LEN 52
00021 
00022 #define MAVLINK_MSG_ID_HOME_POSITION_CRC 104
00023 #define MAVLINK_MSG_ID_242_CRC 104
00024 
00025 #define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4
00026 
00027 #define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
00028         "HOME_POSITION", \
00029         10, \
00030         {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \
00031          { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \
00032          { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \
00033          { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \
00034          { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \
00035          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \
00036          { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \
00037          { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \
00038          { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \
00039          { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \
00040          } \
00041 }
00042 
00043 
00062 static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00063                                                        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)
00064 {
00065 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00066         char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
00067         _mav_put_int32_t(buf, 0, latitude);
00068         _mav_put_int32_t(buf, 4, longitude);
00069         _mav_put_int32_t(buf, 8, altitude);
00070         _mav_put_float(buf, 12, x);
00071         _mav_put_float(buf, 16, y);
00072         _mav_put_float(buf, 20, z);
00073         _mav_put_float(buf, 40, approach_x);
00074         _mav_put_float(buf, 44, approach_y);
00075         _mav_put_float(buf, 48, approach_z);
00076         _mav_put_float_array(buf, 24, q, 4);
00077         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00078 #else
00079         mavlink_home_position_t packet;
00080         packet.latitude = latitude;
00081         packet.longitude = longitude;
00082         packet.altitude = altitude;
00083         packet.x = x;
00084         packet.y = y;
00085         packet.z = z;
00086         packet.approach_x = approach_x;
00087         packet.approach_y = approach_y;
00088         packet.approach_z = approach_z;
00089         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00090         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00091 #endif
00092 
00093         msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
00094 #if MAVLINK_CRC_EXTRA
00095     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
00096 #else
00097     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00098 #endif
00099 }
00100 
00119 static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00120                                                            mavlink_message_t* msg,
00121                                                            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)
00122 {
00123 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00124         char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
00125         _mav_put_int32_t(buf, 0, latitude);
00126         _mav_put_int32_t(buf, 4, longitude);
00127         _mav_put_int32_t(buf, 8, altitude);
00128         _mav_put_float(buf, 12, x);
00129         _mav_put_float(buf, 16, y);
00130         _mav_put_float(buf, 20, z);
00131         _mav_put_float(buf, 40, approach_x);
00132         _mav_put_float(buf, 44, approach_y);
00133         _mav_put_float(buf, 48, approach_z);
00134         _mav_put_float_array(buf, 24, q, 4);
00135         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00136 #else
00137         mavlink_home_position_t packet;
00138         packet.latitude = latitude;
00139         packet.longitude = longitude;
00140         packet.altitude = altitude;
00141         packet.x = x;
00142         packet.y = y;
00143         packet.z = z;
00144         packet.approach_x = approach_x;
00145         packet.approach_y = approach_y;
00146         packet.approach_z = approach_z;
00147         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00148         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00149 #endif
00150 
00151         msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
00152 #if MAVLINK_CRC_EXTRA
00153     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
00154 #else
00155     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00156 #endif
00157 }
00158 
00167 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)
00168 {
00169         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);
00170 }
00171 
00181 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)
00182 {
00183         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);
00184 }
00185 
00201 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00202 
00203 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)
00204 {
00205 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00206         char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
00207         _mav_put_int32_t(buf, 0, latitude);
00208         _mav_put_int32_t(buf, 4, longitude);
00209         _mav_put_int32_t(buf, 8, altitude);
00210         _mav_put_float(buf, 12, x);
00211         _mav_put_float(buf, 16, y);
00212         _mav_put_float(buf, 20, z);
00213         _mav_put_float(buf, 40, approach_x);
00214         _mav_put_float(buf, 44, approach_y);
00215         _mav_put_float(buf, 48, approach_z);
00216         _mav_put_float_array(buf, 24, q, 4);
00217 #if MAVLINK_CRC_EXTRA
00218     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
00219 #else
00220     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00221 #endif
00222 #else
00223         mavlink_home_position_t packet;
00224         packet.latitude = latitude;
00225         packet.longitude = longitude;
00226         packet.altitude = altitude;
00227         packet.x = x;
00228         packet.y = y;
00229         packet.z = z;
00230         packet.approach_x = approach_x;
00231         packet.approach_y = approach_y;
00232         packet.approach_z = approach_z;
00233         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00234 #if MAVLINK_CRC_EXTRA
00235     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
00236 #else
00237     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00238 #endif
00239 #endif
00240 }
00241 
00242 #if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00243 /*
00244   This varient of _send() can be used to save stack space by re-using
00245   memory from the receive buffer.  The caller provides a
00246   mavlink_message_t which is the size of a full mavlink message. This
00247   is usually the receive buffer for the channel, and allows a reply to an
00248   incoming message with minimum stack space usage.
00249  */
00250 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)
00251 {
00252 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00253         char *buf = (char *)msgbuf;
00254         _mav_put_int32_t(buf, 0, latitude);
00255         _mav_put_int32_t(buf, 4, longitude);
00256         _mav_put_int32_t(buf, 8, altitude);
00257         _mav_put_float(buf, 12, x);
00258         _mav_put_float(buf, 16, y);
00259         _mav_put_float(buf, 20, z);
00260         _mav_put_float(buf, 40, approach_x);
00261         _mav_put_float(buf, 44, approach_y);
00262         _mav_put_float(buf, 48, approach_z);
00263         _mav_put_float_array(buf, 24, q, 4);
00264 #if MAVLINK_CRC_EXTRA
00265     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
00266 #else
00267     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00268 #endif
00269 #else
00270         mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf;
00271         packet->latitude = latitude;
00272         packet->longitude = longitude;
00273         packet->altitude = altitude;
00274         packet->x = x;
00275         packet->y = y;
00276         packet->z = z;
00277         packet->approach_x = approach_x;
00278         packet->approach_y = approach_y;
00279         packet->approach_z = approach_z;
00280         mav_array_memcpy(packet->q, q, sizeof(float)*4);
00281 #if MAVLINK_CRC_EXTRA
00282     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
00283 #else
00284     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
00285 #endif
00286 #endif
00287 }
00288 #endif
00289 
00290 #endif
00291 
00292 // MESSAGE HOME_POSITION UNPACKING
00293 
00294 
00300 static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg)
00301 {
00302         return _MAV_RETURN_int32_t(msg,  0);
00303 }
00304 
00310 static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg)
00311 {
00312         return _MAV_RETURN_int32_t(msg,  4);
00313 }
00314 
00320 static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg)
00321 {
00322         return _MAV_RETURN_int32_t(msg,  8);
00323 }
00324 
00330 static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg)
00331 {
00332         return _MAV_RETURN_float(msg,  12);
00333 }
00334 
00340 static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg)
00341 {
00342         return _MAV_RETURN_float(msg,  16);
00343 }
00344 
00350 static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg)
00351 {
00352         return _MAV_RETURN_float(msg,  20);
00353 }
00354 
00360 static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q)
00361 {
00362         return _MAV_RETURN_float_array(msg, q, 4,  24);
00363 }
00364 
00370 static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg)
00371 {
00372         return _MAV_RETURN_float(msg,  40);
00373 }
00374 
00380 static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg)
00381 {
00382         return _MAV_RETURN_float(msg,  44);
00383 }
00384 
00390 static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg)
00391 {
00392         return _MAV_RETURN_float(msg,  48);
00393 }
00394 
00401 static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position)
00402 {
00403 #if MAVLINK_NEED_BYTE_SWAP
00404         home_position->latitude = mavlink_msg_home_position_get_latitude(msg);
00405         home_position->longitude = mavlink_msg_home_position_get_longitude(msg);
00406         home_position->altitude = mavlink_msg_home_position_get_altitude(msg);
00407         home_position->x = mavlink_msg_home_position_get_x(msg);
00408         home_position->y = mavlink_msg_home_position_get_y(msg);
00409         home_position->z = mavlink_msg_home_position_get_z(msg);
00410         mavlink_msg_home_position_get_q(msg, home_position->q);
00411         home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg);
00412         home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg);
00413         home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg);
00414 #else
00415         memcpy(home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HOME_POSITION_LEN);
00416 #endif
00417 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35