mavlink_msg_safety_set_allowed_area.h
Go to the documentation of this file.
00001 // MESSAGE SAFETY_SET_ALLOWED_AREA PACKING
00002 
00003 #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54
00004 
00005 typedef struct __mavlink_safety_set_allowed_area_t
00006 {
00007  float p1x; /*< x position 1 / Latitude 1*/
00008  float p1y; /*< y position 1 / Longitude 1*/
00009  float p1z; /*< z position 1 / Altitude 1*/
00010  float p2x; /*< x position 2 / Latitude 2*/
00011  float p2y; /*< y position 2 / Longitude 2*/
00012  float p2z; /*< z position 2 / Altitude 2*/
00013  uint8_t target_system; /*< System ID*/
00014  uint8_t target_component; /*< Component ID*/
00015  uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/
00016 } mavlink_safety_set_allowed_area_t;
00017 
00018 #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27
00019 #define MAVLINK_MSG_ID_54_LEN 27
00020 
00021 #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15
00022 #define MAVLINK_MSG_ID_54_CRC 15
00023 
00024 
00025 
00026 #define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \
00027         "SAFETY_SET_ALLOWED_AREA", \
00028         9, \
00029         {  { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \
00030          { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \
00031          { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \
00032          { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \
00033          { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \
00034          { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \
00035          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \
00036          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \
00037          { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \
00038          } \
00039 }
00040 
00041 
00059 static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00060                                                        uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
00061 {
00062 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00063         char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN];
00064         _mav_put_float(buf, 0, p1x);
00065         _mav_put_float(buf, 4, p1y);
00066         _mav_put_float(buf, 8, p1z);
00067         _mav_put_float(buf, 12, p2x);
00068         _mav_put_float(buf, 16, p2y);
00069         _mav_put_float(buf, 20, p2z);
00070         _mav_put_uint8_t(buf, 24, target_system);
00071         _mav_put_uint8_t(buf, 25, target_component);
00072         _mav_put_uint8_t(buf, 26, frame);
00073 
00074         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00075 #else
00076         mavlink_safety_set_allowed_area_t packet;
00077         packet.p1x = p1x;
00078         packet.p1y = p1y;
00079         packet.p1z = p1z;
00080         packet.p2x = p2x;
00081         packet.p2y = p2y;
00082         packet.p2z = p2z;
00083         packet.target_system = target_system;
00084         packet.target_component = target_component;
00085         packet.frame = frame;
00086 
00087         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00088 #endif
00089 
00090         msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
00091 #if MAVLINK_CRC_EXTRA
00092     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
00093 #else
00094     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00095 #endif
00096 }
00097 
00115 static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00116                                                            mavlink_message_t* msg,
00117                                                            uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z)
00118 {
00119 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00120         char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN];
00121         _mav_put_float(buf, 0, p1x);
00122         _mav_put_float(buf, 4, p1y);
00123         _mav_put_float(buf, 8, p1z);
00124         _mav_put_float(buf, 12, p2x);
00125         _mav_put_float(buf, 16, p2y);
00126         _mav_put_float(buf, 20, p2z);
00127         _mav_put_uint8_t(buf, 24, target_system);
00128         _mav_put_uint8_t(buf, 25, target_component);
00129         _mav_put_uint8_t(buf, 26, frame);
00130 
00131         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00132 #else
00133         mavlink_safety_set_allowed_area_t packet;
00134         packet.p1x = p1x;
00135         packet.p1y = p1y;
00136         packet.p1z = p1z;
00137         packet.p2x = p2x;
00138         packet.p2y = p2y;
00139         packet.p2z = p2z;
00140         packet.target_system = target_system;
00141         packet.target_component = target_component;
00142         packet.frame = frame;
00143 
00144         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00145 #endif
00146 
00147         msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
00148 #if MAVLINK_CRC_EXTRA
00149     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
00150 #else
00151     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00152 #endif
00153 }
00154 
00163 static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
00164 {
00165         return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z);
00166 }
00167 
00177 static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
00178 {
00179         return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z);
00180 }
00181 
00196 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00197 
00198 static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
00199 {
00200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00201         char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN];
00202         _mav_put_float(buf, 0, p1x);
00203         _mav_put_float(buf, 4, p1y);
00204         _mav_put_float(buf, 8, p1z);
00205         _mav_put_float(buf, 12, p2x);
00206         _mav_put_float(buf, 16, p2y);
00207         _mav_put_float(buf, 20, p2z);
00208         _mav_put_uint8_t(buf, 24, target_system);
00209         _mav_put_uint8_t(buf, 25, target_component);
00210         _mav_put_uint8_t(buf, 26, frame);
00211 
00212 #if MAVLINK_CRC_EXTRA
00213     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
00214 #else
00215     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00216 #endif
00217 #else
00218         mavlink_safety_set_allowed_area_t packet;
00219         packet.p1x = p1x;
00220         packet.p1y = p1y;
00221         packet.p1z = p1z;
00222         packet.p2x = p2x;
00223         packet.p2y = p2y;
00224         packet.p2z = p2z;
00225         packet.target_system = target_system;
00226         packet.target_component = target_component;
00227         packet.frame = frame;
00228 
00229 #if MAVLINK_CRC_EXTRA
00230     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
00231 #else
00232     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00233 #endif
00234 #endif
00235 }
00236 
00237 #if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00238 /*
00239   This varient of _send() can be used to save stack space by re-using
00240   memory from the receive buffer.  The caller provides a
00241   mavlink_message_t which is the size of a full mavlink message. This
00242   is usually the receive buffer for the channel, and allows a reply to an
00243   incoming message with minimum stack space usage.
00244  */
00245 static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
00246 {
00247 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00248         char *buf = (char *)msgbuf;
00249         _mav_put_float(buf, 0, p1x);
00250         _mav_put_float(buf, 4, p1y);
00251         _mav_put_float(buf, 8, p1z);
00252         _mav_put_float(buf, 12, p2x);
00253         _mav_put_float(buf, 16, p2y);
00254         _mav_put_float(buf, 20, p2z);
00255         _mav_put_uint8_t(buf, 24, target_system);
00256         _mav_put_uint8_t(buf, 25, target_component);
00257         _mav_put_uint8_t(buf, 26, frame);
00258 
00259 #if MAVLINK_CRC_EXTRA
00260     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
00261 #else
00262     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00263 #endif
00264 #else
00265         mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf;
00266         packet->p1x = p1x;
00267         packet->p1y = p1y;
00268         packet->p1z = p1z;
00269         packet->p2x = p2x;
00270         packet->p2y = p2y;
00271         packet->p2z = p2z;
00272         packet->target_system = target_system;
00273         packet->target_component = target_component;
00274         packet->frame = frame;
00275 
00276 #if MAVLINK_CRC_EXTRA
00277     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
00278 #else
00279     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00280 #endif
00281 #endif
00282 }
00283 #endif
00284 
00285 #endif
00286 
00287 // MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING
00288 
00289 
00295 static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg)
00296 {
00297         return _MAV_RETURN_uint8_t(msg,  24);
00298 }
00299 
00305 static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg)
00306 {
00307         return _MAV_RETURN_uint8_t(msg,  25);
00308 }
00309 
00315 static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg)
00316 {
00317         return _MAV_RETURN_uint8_t(msg,  26);
00318 }
00319 
00325 static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg)
00326 {
00327         return _MAV_RETURN_float(msg,  0);
00328 }
00329 
00335 static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg)
00336 {
00337         return _MAV_RETURN_float(msg,  4);
00338 }
00339 
00345 static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg)
00346 {
00347         return _MAV_RETURN_float(msg,  8);
00348 }
00349 
00355 static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg)
00356 {
00357         return _MAV_RETURN_float(msg,  12);
00358 }
00359 
00365 static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg)
00366 {
00367         return _MAV_RETURN_float(msg,  16);
00368 }
00369 
00375 static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg)
00376 {
00377         return _MAV_RETURN_float(msg,  20);
00378 }
00379 
00386 static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
00387 {
00388 #if MAVLINK_NEED_BYTE_SWAP
00389         safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg);
00390         safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg);
00391         safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg);
00392         safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg);
00393         safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg);
00394         safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg);
00395         safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg);
00396         safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg);
00397         safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg);
00398 #else
00399         memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
00400 #endif
00401 }


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