mavlink_msg_set_home_position.h
Go to the documentation of this file.
00001 // MESSAGE SET_HOME_POSITION PACKING
00002 
00003 #define MAVLINK_MSG_ID_SET_HOME_POSITION 243
00004 
00005 typedef struct __mavlink_set_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  uint8_t target_system; /*< System ID.*/
00018 } mavlink_set_home_position_t;
00019 
00020 #define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53
00021 #define MAVLINK_MSG_ID_243_LEN 53
00022 
00023 #define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85
00024 #define MAVLINK_MSG_ID_243_CRC 85
00025 
00026 #define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4
00027 
00028 #define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \
00029         "SET_HOME_POSITION", \
00030         11, \
00031         {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \
00032          { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \
00033          { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \
00034          { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \
00035          { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \
00036          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \
00037          { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \
00038          { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \
00039          { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \
00040          { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \
00041          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \
00042          } \
00043 }
00044 
00045 
00065 static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00066                                                        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)
00067 {
00068 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00069         char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
00070         _mav_put_int32_t(buf, 0, latitude);
00071         _mav_put_int32_t(buf, 4, longitude);
00072         _mav_put_int32_t(buf, 8, altitude);
00073         _mav_put_float(buf, 12, x);
00074         _mav_put_float(buf, 16, y);
00075         _mav_put_float(buf, 20, z);
00076         _mav_put_float(buf, 40, approach_x);
00077         _mav_put_float(buf, 44, approach_y);
00078         _mav_put_float(buf, 48, approach_z);
00079         _mav_put_uint8_t(buf, 52, target_system);
00080         _mav_put_float_array(buf, 24, q, 4);
00081         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00082 #else
00083         mavlink_set_home_position_t packet;
00084         packet.latitude = latitude;
00085         packet.longitude = longitude;
00086         packet.altitude = altitude;
00087         packet.x = x;
00088         packet.y = y;
00089         packet.z = z;
00090         packet.approach_x = approach_x;
00091         packet.approach_y = approach_y;
00092         packet.approach_z = approach_z;
00093         packet.target_system = target_system;
00094         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00095         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00096 #endif
00097 
00098         msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION;
00099 #if MAVLINK_CRC_EXTRA
00100     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
00101 #else
00102     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00103 #endif
00104 }
00105 
00125 static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00126                                                            mavlink_message_t* msg,
00127                                                            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)
00128 {
00129 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00130         char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
00131         _mav_put_int32_t(buf, 0, latitude);
00132         _mav_put_int32_t(buf, 4, longitude);
00133         _mav_put_int32_t(buf, 8, altitude);
00134         _mav_put_float(buf, 12, x);
00135         _mav_put_float(buf, 16, y);
00136         _mav_put_float(buf, 20, z);
00137         _mav_put_float(buf, 40, approach_x);
00138         _mav_put_float(buf, 44, approach_y);
00139         _mav_put_float(buf, 48, approach_z);
00140         _mav_put_uint8_t(buf, 52, target_system);
00141         _mav_put_float_array(buf, 24, q, 4);
00142         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00143 #else
00144         mavlink_set_home_position_t packet;
00145         packet.latitude = latitude;
00146         packet.longitude = longitude;
00147         packet.altitude = altitude;
00148         packet.x = x;
00149         packet.y = y;
00150         packet.z = z;
00151         packet.approach_x = approach_x;
00152         packet.approach_y = approach_y;
00153         packet.approach_z = approach_z;
00154         packet.target_system = target_system;
00155         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00156         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00157 #endif
00158 
00159         msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION;
00160 #if MAVLINK_CRC_EXTRA
00161     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
00162 #else
00163     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00164 #endif
00165 }
00166 
00175 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)
00176 {
00177         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);
00178 }
00179 
00189 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)
00190 {
00191         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);
00192 }
00193 
00210 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00211 
00212 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)
00213 {
00214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00215         char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN];
00216         _mav_put_int32_t(buf, 0, latitude);
00217         _mav_put_int32_t(buf, 4, longitude);
00218         _mav_put_int32_t(buf, 8, altitude);
00219         _mav_put_float(buf, 12, x);
00220         _mav_put_float(buf, 16, y);
00221         _mav_put_float(buf, 20, z);
00222         _mav_put_float(buf, 40, approach_x);
00223         _mav_put_float(buf, 44, approach_y);
00224         _mav_put_float(buf, 48, approach_z);
00225         _mav_put_uint8_t(buf, 52, target_system);
00226         _mav_put_float_array(buf, 24, q, 4);
00227 #if MAVLINK_CRC_EXTRA
00228     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
00229 #else
00230     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00231 #endif
00232 #else
00233         mavlink_set_home_position_t packet;
00234         packet.latitude = latitude;
00235         packet.longitude = longitude;
00236         packet.altitude = altitude;
00237         packet.x = x;
00238         packet.y = y;
00239         packet.z = z;
00240         packet.approach_x = approach_x;
00241         packet.approach_y = approach_y;
00242         packet.approach_z = approach_z;
00243         packet.target_system = target_system;
00244         mav_array_memcpy(packet.q, q, sizeof(float)*4);
00245 #if MAVLINK_CRC_EXTRA
00246     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
00247 #else
00248     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00249 #endif
00250 #endif
00251 }
00252 
00253 #if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00254 /*
00255   This varient of _send() can be used to save stack space by re-using
00256   memory from the receive buffer.  The caller provides a
00257   mavlink_message_t which is the size of a full mavlink message. This
00258   is usually the receive buffer for the channel, and allows a reply to an
00259   incoming message with minimum stack space usage.
00260  */
00261 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)
00262 {
00263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00264         char *buf = (char *)msgbuf;
00265         _mav_put_int32_t(buf, 0, latitude);
00266         _mav_put_int32_t(buf, 4, longitude);
00267         _mav_put_int32_t(buf, 8, altitude);
00268         _mav_put_float(buf, 12, x);
00269         _mav_put_float(buf, 16, y);
00270         _mav_put_float(buf, 20, z);
00271         _mav_put_float(buf, 40, approach_x);
00272         _mav_put_float(buf, 44, approach_y);
00273         _mav_put_float(buf, 48, approach_z);
00274         _mav_put_uint8_t(buf, 52, target_system);
00275         _mav_put_float_array(buf, 24, q, 4);
00276 #if MAVLINK_CRC_EXTRA
00277     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
00278 #else
00279     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00280 #endif
00281 #else
00282         mavlink_set_home_position_t *packet = (mavlink_set_home_position_t *)msgbuf;
00283         packet->latitude = latitude;
00284         packet->longitude = longitude;
00285         packet->altitude = altitude;
00286         packet->x = x;
00287         packet->y = y;
00288         packet->z = z;
00289         packet->approach_x = approach_x;
00290         packet->approach_y = approach_y;
00291         packet->approach_z = approach_z;
00292         packet->target_system = target_system;
00293         mav_array_memcpy(packet->q, q, sizeof(float)*4);
00294 #if MAVLINK_CRC_EXTRA
00295     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC);
00296 #else
00297     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00298 #endif
00299 #endif
00300 }
00301 #endif
00302 
00303 #endif
00304 
00305 // MESSAGE SET_HOME_POSITION UNPACKING
00306 
00307 
00313 static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg)
00314 {
00315         return _MAV_RETURN_uint8_t(msg,  52);
00316 }
00317 
00323 static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg)
00324 {
00325         return _MAV_RETURN_int32_t(msg,  0);
00326 }
00327 
00333 static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg)
00334 {
00335         return _MAV_RETURN_int32_t(msg,  4);
00336 }
00337 
00343 static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg)
00344 {
00345         return _MAV_RETURN_int32_t(msg,  8);
00346 }
00347 
00353 static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg)
00354 {
00355         return _MAV_RETURN_float(msg,  12);
00356 }
00357 
00363 static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg)
00364 {
00365         return _MAV_RETURN_float(msg,  16);
00366 }
00367 
00373 static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg)
00374 {
00375         return _MAV_RETURN_float(msg,  20);
00376 }
00377 
00383 static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q)
00384 {
00385         return _MAV_RETURN_float_array(msg, q, 4,  24);
00386 }
00387 
00393 static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg)
00394 {
00395         return _MAV_RETURN_float(msg,  40);
00396 }
00397 
00403 static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg)
00404 {
00405         return _MAV_RETURN_float(msg,  44);
00406 }
00407 
00413 static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg)
00414 {
00415         return _MAV_RETURN_float(msg,  48);
00416 }
00417 
00424 static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position)
00425 {
00426 #if MAVLINK_NEED_BYTE_SWAP
00427         set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg);
00428         set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg);
00429         set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg);
00430         set_home_position->x = mavlink_msg_set_home_position_get_x(msg);
00431         set_home_position->y = mavlink_msg_set_home_position_get_y(msg);
00432         set_home_position->z = mavlink_msg_set_home_position_get_z(msg);
00433         mavlink_msg_set_home_position_get_q(msg, set_home_position->q);
00434         set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg);
00435         set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg);
00436         set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg);
00437         set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg);
00438 #else
00439         memcpy(set_home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_HOME_POSITION_LEN);
00440 #endif
00441 }


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