00001
00002
00003 #define MAVLINK_MSG_ID_DISTANCE_SENSOR 132
00004
00005 typedef struct __mavlink_distance_sensor_t
00006 {
00007 uint32_t time_boot_ms;
00008 uint16_t min_distance;
00009 uint16_t max_distance;
00010 uint16_t current_distance;
00011 uint8_t type;
00012 uint8_t id;
00013 uint8_t orientation;
00014 uint8_t covariance;
00015 } mavlink_distance_sensor_t;
00016
00017 #define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14
00018 #define MAVLINK_MSG_ID_132_LEN 14
00019
00020 #define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85
00021 #define MAVLINK_MSG_ID_132_CRC 85
00022
00023
00024
00025 #define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \
00026 "DISTANCE_SENSOR", \
00027 8, \
00028 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \
00029 { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \
00030 { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \
00031 { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \
00032 { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \
00033 { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \
00034 { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \
00035 { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \
00036 } \
00037 }
00038
00039
00056 static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00057 uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
00058 {
00059 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00060 char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
00061 _mav_put_uint32_t(buf, 0, time_boot_ms);
00062 _mav_put_uint16_t(buf, 4, min_distance);
00063 _mav_put_uint16_t(buf, 6, max_distance);
00064 _mav_put_uint16_t(buf, 8, current_distance);
00065 _mav_put_uint8_t(buf, 10, type);
00066 _mav_put_uint8_t(buf, 11, id);
00067 _mav_put_uint8_t(buf, 12, orientation);
00068 _mav_put_uint8_t(buf, 13, covariance);
00069
00070 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00071 #else
00072 mavlink_distance_sensor_t packet;
00073 packet.time_boot_ms = time_boot_ms;
00074 packet.min_distance = min_distance;
00075 packet.max_distance = max_distance;
00076 packet.current_distance = current_distance;
00077 packet.type = type;
00078 packet.id = id;
00079 packet.orientation = orientation;
00080 packet.covariance = covariance;
00081
00082 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00083 #endif
00084
00085 msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
00086 #if MAVLINK_CRC_EXTRA
00087 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
00088 #else
00089 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00090 #endif
00091 }
00092
00109 static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00110 mavlink_message_t* msg,
00111 uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance)
00112 {
00113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00114 char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
00115 _mav_put_uint32_t(buf, 0, time_boot_ms);
00116 _mav_put_uint16_t(buf, 4, min_distance);
00117 _mav_put_uint16_t(buf, 6, max_distance);
00118 _mav_put_uint16_t(buf, 8, current_distance);
00119 _mav_put_uint8_t(buf, 10, type);
00120 _mav_put_uint8_t(buf, 11, id);
00121 _mav_put_uint8_t(buf, 12, orientation);
00122 _mav_put_uint8_t(buf, 13, covariance);
00123
00124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00125 #else
00126 mavlink_distance_sensor_t packet;
00127 packet.time_boot_ms = time_boot_ms;
00128 packet.min_distance = min_distance;
00129 packet.max_distance = max_distance;
00130 packet.current_distance = current_distance;
00131 packet.type = type;
00132 packet.id = id;
00133 packet.orientation = orientation;
00134 packet.covariance = covariance;
00135
00136 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00137 #endif
00138
00139 msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
00140 #if MAVLINK_CRC_EXTRA
00141 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
00142 #else
00143 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00144 #endif
00145 }
00146
00155 static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
00156 {
00157 return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance);
00158 }
00159
00169 static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
00170 {
00171 return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance);
00172 }
00173
00187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00188
00189 static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
00190 {
00191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00192 char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
00193 _mav_put_uint32_t(buf, 0, time_boot_ms);
00194 _mav_put_uint16_t(buf, 4, min_distance);
00195 _mav_put_uint16_t(buf, 6, max_distance);
00196 _mav_put_uint16_t(buf, 8, current_distance);
00197 _mav_put_uint8_t(buf, 10, type);
00198 _mav_put_uint8_t(buf, 11, id);
00199 _mav_put_uint8_t(buf, 12, orientation);
00200 _mav_put_uint8_t(buf, 13, covariance);
00201
00202 #if MAVLINK_CRC_EXTRA
00203 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
00204 #else
00205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00206 #endif
00207 #else
00208 mavlink_distance_sensor_t packet;
00209 packet.time_boot_ms = time_boot_ms;
00210 packet.min_distance = min_distance;
00211 packet.max_distance = max_distance;
00212 packet.current_distance = current_distance;
00213 packet.type = type;
00214 packet.id = id;
00215 packet.orientation = orientation;
00216 packet.covariance = covariance;
00217
00218 #if MAVLINK_CRC_EXTRA
00219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
00220 #else
00221 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00222 #endif
00223 #endif
00224 }
00225
00226 #if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00227
00228
00229
00230
00231
00232
00233
00234 static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
00235 {
00236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00237 char *buf = (char *)msgbuf;
00238 _mav_put_uint32_t(buf, 0, time_boot_ms);
00239 _mav_put_uint16_t(buf, 4, min_distance);
00240 _mav_put_uint16_t(buf, 6, max_distance);
00241 _mav_put_uint16_t(buf, 8, current_distance);
00242 _mav_put_uint8_t(buf, 10, type);
00243 _mav_put_uint8_t(buf, 11, id);
00244 _mav_put_uint8_t(buf, 12, orientation);
00245 _mav_put_uint8_t(buf, 13, covariance);
00246
00247 #if MAVLINK_CRC_EXTRA
00248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
00249 #else
00250 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00251 #endif
00252 #else
00253 mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf;
00254 packet->time_boot_ms = time_boot_ms;
00255 packet->min_distance = min_distance;
00256 packet->max_distance = max_distance;
00257 packet->current_distance = current_distance;
00258 packet->type = type;
00259 packet->id = id;
00260 packet->orientation = orientation;
00261 packet->covariance = covariance;
00262
00263 #if MAVLINK_CRC_EXTRA
00264 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
00265 #else
00266 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00267 #endif
00268 #endif
00269 }
00270 #endif
00271
00272 #endif
00273
00274
00275
00276
00282 static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg)
00283 {
00284 return _MAV_RETURN_uint32_t(msg, 0);
00285 }
00286
00292 static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg)
00293 {
00294 return _MAV_RETURN_uint16_t(msg, 4);
00295 }
00296
00302 static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg)
00303 {
00304 return _MAV_RETURN_uint16_t(msg, 6);
00305 }
00306
00312 static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg)
00313 {
00314 return _MAV_RETURN_uint16_t(msg, 8);
00315 }
00316
00322 static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg)
00323 {
00324 return _MAV_RETURN_uint8_t(msg, 10);
00325 }
00326
00332 static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg)
00333 {
00334 return _MAV_RETURN_uint8_t(msg, 11);
00335 }
00336
00342 static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg)
00343 {
00344 return _MAV_RETURN_uint8_t(msg, 12);
00345 }
00346
00352 static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg)
00353 {
00354 return _MAV_RETURN_uint8_t(msg, 13);
00355 }
00356
00363 static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor)
00364 {
00365 #if MAVLINK_NEED_BYTE_SWAP
00366 distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg);
00367 distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg);
00368 distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg);
00369 distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg);
00370 distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg);
00371 distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg);
00372 distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg);
00373 distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg);
00374 #else
00375 memcpy(distance_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
00376 #endif
00377 }