3 #define MAVLINK_MSG_ID_UAV_STATUS 193
15 #define MAVLINK_MSG_ID_UAV_STATUS_LEN 21
16 #define MAVLINK_MSG_ID_193_LEN 21
18 #define MAVLINK_MSG_ID_UAV_STATUS_CRC 160
19 #define MAVLINK_MSG_ID_193_CRC 160
23 #define MAVLINK_MESSAGE_INFO_UAV_STATUS { \
26 { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_uav_status_t, latitude) }, \
27 { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_uav_status_t, longitude) }, \
28 { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_uav_status_t, altitude) }, \
29 { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_uav_status_t, speed) }, \
30 { "course", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_uav_status_t, course) }, \
31 { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_uav_status_t, target) }, \
50 static inline uint16_t mavlink_msg_uav_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51 uint8_t target,
float latitude,
float longitude,
float altitude,
float speed,
float course)
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
97 static inline uint16_t mavlink_msg_uav_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98 mavlink_message_t* msg,
99 uint8_t target,
float latitude,
float longitude,
float altitude,
float speed,
float course)
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
116 packet.
speed = speed;
124 #if MAVLINK_CRC_EXTRA
139 static inline uint16_t mavlink_msg_uav_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_uav_status_t* uav_status)
153 static inline uint16_t mavlink_msg_uav_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_uav_status_t* uav_status)
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
171 static inline void mavlink_msg_uav_status_send(
mavlink_channel_t chan, uint8_t target,
float latitude,
float longitude,
float altitude,
float speed,
float course)
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 #if MAVLINK_CRC_EXTRA
192 packet.
speed = speed;
196 #if MAVLINK_CRC_EXTRA
204 #if MAVLINK_MSG_ID_UAV_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
212 static inline void mavlink_msg_uav_status_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t target,
float latitude,
float longitude,
float altitude,
float speed,
float course)
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215 char *buf = (
char *)msgbuf;
223 #if MAVLINK_CRC_EXTRA
233 packet->
speed = speed;
237 #if MAVLINK_CRC_EXTRA
256 static inline uint8_t mavlink_msg_uav_status_get_target(
const mavlink_message_t* msg)
266 static inline float mavlink_msg_uav_status_get_latitude(
const mavlink_message_t* msg)
268 return _MAV_RETURN_float(msg, 0);
276 static inline float mavlink_msg_uav_status_get_longitude(
const mavlink_message_t* msg)
278 return _MAV_RETURN_float(msg, 4);
286 static inline float mavlink_msg_uav_status_get_altitude(
const mavlink_message_t* msg)
288 return _MAV_RETURN_float(msg, 8);
296 static inline float mavlink_msg_uav_status_get_speed(
const mavlink_message_t* msg)
298 return _MAV_RETURN_float(msg, 12);
306 static inline float mavlink_msg_uav_status_get_course(
const mavlink_message_t* msg)
308 return _MAV_RETURN_float(msg, 16);
317 static inline void mavlink_msg_uav_status_decode(
const mavlink_message_t* msg,
mavlink_uav_status_t* uav_status)
319 #if MAVLINK_NEED_BYTE_SWAP
320 uav_status->
latitude = mavlink_msg_uav_status_get_latitude(msg);
321 uav_status->
longitude = mavlink_msg_uav_status_get_longitude(msg);
322 uav_status->
altitude = mavlink_msg_uav_status_get_altitude(msg);
323 uav_status->
speed = mavlink_msg_uav_status_get_speed(msg);
324 uav_status->
course = mavlink_msg_uav_status_get_course(msg);
325 uav_status->
target = mavlink_msg_uav_status_get_target(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
struct __mavlink_uav_status_t mavlink_uav_status_t
float course
Course UAV.
Definition: mavlink_msg_uav_status.h:11
Definition: mavlink_msg_uav_status.h:5
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
uint8_t target
The ID system reporting the action.
Definition: mavlink_msg_uav_status.h:12
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
float latitude
Latitude UAV.
Definition: mavlink_msg_uav_status.h:7
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float longitude
Longitude UAV.
Definition: mavlink_msg_uav_status.h:8
#define MAVLINK_MSG_ID_UAV_STATUS
Definition: mavlink_msg_uav_status.h:3
#define MAVLINK_MSG_ID_UAV_STATUS_CRC
Definition: mavlink_msg_uav_status.h:18
#define MAVLINK_MSG_ID_UAV_STATUS_LEN
Definition: mavlink_msg_uav_status.h:15
float speed
Speed UAV.
Definition: mavlink_msg_uav_status.h:10
float altitude
Altitude UAV.
Definition: mavlink_msg_uav_status.h:9
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71