Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependents: mavlink F429ZI_LCD_demo
Fork of mavlink_bridge by
mavlink_msg_safety_allowed_area.h
00001 // MESSAGE SAFETY_ALLOWED_AREA PACKING 00002 00003 #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 00004 00005 typedef struct __mavlink_safety_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 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.*/ 00014 } mavlink_safety_allowed_area_t; 00015 00016 #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 00017 #define MAVLINK_MSG_ID_55_LEN 25 00018 00019 #define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 00020 #define MAVLINK_MSG_ID_55_CRC 3 00021 00022 00023 00024 #define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ 00025 "SAFETY_ALLOWED_AREA", \ 00026 7, \ 00027 { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ 00028 { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ 00029 { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ 00030 { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ 00031 { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ 00032 { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ 00033 { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ 00034 } \ 00035 } 00036 00037 00038 /** 00039 * @brief Pack a safety_allowed_area message 00040 * @param system_id ID of this system 00041 * @param component_id ID of this component (e.g. 200 for IMU) 00042 * @param msg The MAVLink message to compress the data into 00043 * 00044 * @param 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. 00045 * @param p1x x position 1 / Latitude 1 00046 * @param p1y y position 1 / Longitude 1 00047 * @param p1z z position 1 / Altitude 1 00048 * @param p2x x position 2 / Latitude 2 00049 * @param p2y y position 2 / Longitude 2 00050 * @param p2z z position 2 / Altitude 2 00051 * @return length of the message in bytes (excluding serial stream start sign) 00052 */ 00053 static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 00054 uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) 00055 { 00056 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00057 char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; 00058 _mav_put_float(buf, 0, p1x); 00059 _mav_put_float(buf, 4, p1y); 00060 _mav_put_float(buf, 8, p1z); 00061 _mav_put_float(buf, 12, p2x); 00062 _mav_put_float(buf, 16, p2y); 00063 _mav_put_float(buf, 20, p2z); 00064 _mav_put_uint8_t(buf, 24, frame); 00065 00066 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00067 #else 00068 mavlink_safety_allowed_area_t packet; 00069 packet.p1x = p1x; 00070 packet.p1y = p1y; 00071 packet.p1z = p1z; 00072 packet.p2x = p2x; 00073 packet.p2y = p2y; 00074 packet.p2z = p2z; 00075 packet.frame = frame; 00076 00077 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00078 #endif 00079 00080 msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; 00081 #if MAVLINK_CRC_EXTRA 00082 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); 00083 #else 00084 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00085 #endif 00086 } 00087 00088 /** 00089 * @brief Pack a safety_allowed_area message on a channel 00090 * @param system_id ID of this system 00091 * @param component_id ID of this component (e.g. 200 for IMU) 00092 * @param chan The MAVLink channel this message will be sent over 00093 * @param msg The MAVLink message to compress the data into 00094 * @param 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. 00095 * @param p1x x position 1 / Latitude 1 00096 * @param p1y y position 1 / Longitude 1 00097 * @param p1z z position 1 / Altitude 1 00098 * @param p2x x position 2 / Latitude 2 00099 * @param p2y y position 2 / Longitude 2 00100 * @param p2z z position 2 / Altitude 2 00101 * @return length of the message in bytes (excluding serial stream start sign) 00102 */ 00103 static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 00104 mavlink_message_t* msg, 00105 uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) 00106 { 00107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00108 char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; 00109 _mav_put_float(buf, 0, p1x); 00110 _mav_put_float(buf, 4, p1y); 00111 _mav_put_float(buf, 8, p1z); 00112 _mav_put_float(buf, 12, p2x); 00113 _mav_put_float(buf, 16, p2y); 00114 _mav_put_float(buf, 20, p2z); 00115 _mav_put_uint8_t(buf, 24, frame); 00116 00117 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00118 #else 00119 mavlink_safety_allowed_area_t packet; 00120 packet.p1x = p1x; 00121 packet.p1y = p1y; 00122 packet.p1z = p1z; 00123 packet.p2x = p2x; 00124 packet.p2y = p2y; 00125 packet.p2z = p2z; 00126 packet.frame = frame; 00127 00128 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00129 #endif 00130 00131 msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; 00132 #if MAVLINK_CRC_EXTRA 00133 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); 00134 #else 00135 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00136 #endif 00137 } 00138 00139 /** 00140 * @brief Encode a safety_allowed_area struct 00141 * 00142 * @param system_id ID of this system 00143 * @param component_id ID of this component (e.g. 200 for IMU) 00144 * @param msg The MAVLink message to compress the data into 00145 * @param safety_allowed_area C-struct to read the message contents from 00146 */ 00147 static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) 00148 { 00149 return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); 00150 } 00151 00152 /** 00153 * @brief Encode a safety_allowed_area struct on a channel 00154 * 00155 * @param system_id ID of this system 00156 * @param component_id ID of this component (e.g. 200 for IMU) 00157 * @param chan The MAVLink channel this message will be sent over 00158 * @param msg The MAVLink message to compress the data into 00159 * @param safety_allowed_area C-struct to read the message contents from 00160 */ 00161 static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) 00162 { 00163 return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); 00164 } 00165 00166 /** 00167 * @brief Send a safety_allowed_area message 00168 * @param chan MAVLink channel to send the message 00169 * 00170 * @param 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. 00171 * @param p1x x position 1 / Latitude 1 00172 * @param p1y y position 1 / Longitude 1 00173 * @param p1z z position 1 / Altitude 1 00174 * @param p2x x position 2 / Latitude 2 00175 * @param p2y y position 2 / Longitude 2 00176 * @param p2z z position 2 / Altitude 2 00177 */ 00178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00179 00180 static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) 00181 { 00182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00183 char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; 00184 _mav_put_float(buf, 0, p1x); 00185 _mav_put_float(buf, 4, p1y); 00186 _mav_put_float(buf, 8, p1z); 00187 _mav_put_float(buf, 12, p2x); 00188 _mav_put_float(buf, 16, p2y); 00189 _mav_put_float(buf, 20, p2z); 00190 _mav_put_uint8_t(buf, 24, frame); 00191 00192 #if MAVLINK_CRC_EXTRA 00193 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); 00194 #else 00195 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00196 #endif 00197 #else 00198 mavlink_safety_allowed_area_t packet; 00199 packet.p1x = p1x; 00200 packet.p1y = p1y; 00201 packet.p1z = p1z; 00202 packet.p2x = p2x; 00203 packet.p2y = p2y; 00204 packet.p2z = p2z; 00205 packet.frame = frame; 00206 00207 #if MAVLINK_CRC_EXTRA 00208 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); 00209 #else 00210 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00211 #endif 00212 #endif 00213 } 00214 00215 #if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN 00216 /* 00217 This varient of _send() can be used to save stack space by re-using 00218 memory from the receive buffer. The caller provides a 00219 mavlink_message_t which is the size of a full mavlink message. This 00220 is usually the receive buffer for the channel, and allows a reply to an 00221 incoming message with minimum stack space usage. 00222 */ 00223 static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) 00224 { 00225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 00226 char *buf = (char *)msgbuf; 00227 _mav_put_float(buf, 0, p1x); 00228 _mav_put_float(buf, 4, p1y); 00229 _mav_put_float(buf, 8, p1z); 00230 _mav_put_float(buf, 12, p2x); 00231 _mav_put_float(buf, 16, p2y); 00232 _mav_put_float(buf, 20, p2z); 00233 _mav_put_uint8_t(buf, 24, frame); 00234 00235 #if MAVLINK_CRC_EXTRA 00236 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); 00237 #else 00238 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00239 #endif 00240 #else 00241 mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf; 00242 packet->p1x = p1x; 00243 packet->p1y = p1y; 00244 packet->p1z = p1z; 00245 packet->p2x = p2x; 00246 packet->p2y = p2y; 00247 packet->p2z = p2z; 00248 packet->frame = frame; 00249 00250 #if MAVLINK_CRC_EXTRA 00251 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); 00252 #else 00253 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00254 #endif 00255 #endif 00256 } 00257 #endif 00258 00259 #endif 00260 00261 // MESSAGE SAFETY_ALLOWED_AREA UNPACKING 00262 00263 00264 /** 00265 * @brief Get field frame from safety_allowed_area message 00266 * 00267 * @return 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. 00268 */ 00269 static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) 00270 { 00271 return _MAV_RETURN_uint8_t(msg, 24); 00272 } 00273 00274 /** 00275 * @brief Get field p1x from safety_allowed_area message 00276 * 00277 * @return x position 1 / Latitude 1 00278 */ 00279 static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) 00280 { 00281 return _MAV_RETURN_float(msg, 0); 00282 } 00283 00284 /** 00285 * @brief Get field p1y from safety_allowed_area message 00286 * 00287 * @return y position 1 / Longitude 1 00288 */ 00289 static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) 00290 { 00291 return _MAV_RETURN_float(msg, 4); 00292 } 00293 00294 /** 00295 * @brief Get field p1z from safety_allowed_area message 00296 * 00297 * @return z position 1 / Altitude 1 00298 */ 00299 static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) 00300 { 00301 return _MAV_RETURN_float(msg, 8); 00302 } 00303 00304 /** 00305 * @brief Get field p2x from safety_allowed_area message 00306 * 00307 * @return x position 2 / Latitude 2 00308 */ 00309 static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) 00310 { 00311 return _MAV_RETURN_float(msg, 12); 00312 } 00313 00314 /** 00315 * @brief Get field p2y from safety_allowed_area message 00316 * 00317 * @return y position 2 / Longitude 2 00318 */ 00319 static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) 00320 { 00321 return _MAV_RETURN_float(msg, 16); 00322 } 00323 00324 /** 00325 * @brief Get field p2z from safety_allowed_area message 00326 * 00327 * @return z position 2 / Altitude 2 00328 */ 00329 static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) 00330 { 00331 return _MAV_RETURN_float(msg, 20); 00332 } 00333 00334 /** 00335 * @brief Decode a safety_allowed_area message into a struct 00336 * 00337 * @param msg The message to decode 00338 * @param safety_allowed_area C-struct to decode the message contents into 00339 */ 00340 static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) 00341 { 00342 #if MAVLINK_NEED_BYTE_SWAP 00343 safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); 00344 safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); 00345 safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); 00346 safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); 00347 safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); 00348 safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); 00349 safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); 00350 #else 00351 memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); 00352 #endif 00353 }
Generated on Tue Jul 12 2022 22:02:42 by
1.7.2
