3 #define MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION 186
12 #define MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION_LEN 9
13 #define MAVLINK_MSG_ID_186_LEN 9
15 #define MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION_CRC 101
16 #define MAVLINK_MSG_ID_186_CRC 101
20 #define MAVLINK_MESSAGE_INFO_SLUGS_MOBILE_LOCATION { \
21 "SLUGS_MOBILE_LOCATION", \
23 { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_slugs_mobile_location_t, latitude) }, \
24 { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_slugs_mobile_location_t, longitude) }, \
25 { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_slugs_mobile_location_t, target) }, \
41 static inline uint16_t mavlink_msg_slugs_mobile_location_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42 uint8_t target,
float latitude,
float longitude)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 static inline uint16_t mavlink_msg_slugs_mobile_location_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
80 mavlink_message_t* msg,
81 uint8_t target,
float latitude,
float longitude)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100 #if MAVLINK_CRC_EXTRA
115 static inline uint16_t mavlink_msg_slugs_mobile_location_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_slugs_mobile_location_t* slugs_mobile_location)
117 return mavlink_msg_slugs_mobile_location_pack(system_id, component_id, msg, slugs_mobile_location->
target, slugs_mobile_location->
latitude, slugs_mobile_location->
longitude);
129 static inline uint16_t mavlink_msg_slugs_mobile_location_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_slugs_mobile_location_t* slugs_mobile_location)
131 return mavlink_msg_slugs_mobile_location_pack_chan(system_id, component_id, chan, msg, slugs_mobile_location->
target, slugs_mobile_location->
latitude, slugs_mobile_location->
longitude);
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
144 static inline void mavlink_msg_slugs_mobile_location_send(
mavlink_channel_t chan, uint8_t target,
float latitude,
float longitude)
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 #if MAVLINK_CRC_EXTRA
163 #if MAVLINK_CRC_EXTRA
171 #if MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
179 static inline void mavlink_msg_slugs_mobile_location_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t target,
float latitude,
float longitude)
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
187 #if MAVLINK_CRC_EXTRA
198 #if MAVLINK_CRC_EXTRA
217 static inline uint8_t mavlink_msg_slugs_mobile_location_get_target(
const mavlink_message_t* msg)
227 static inline float mavlink_msg_slugs_mobile_location_get_latitude(
const mavlink_message_t* msg)
229 return _MAV_RETURN_float(msg, 0);
237 static inline float mavlink_msg_slugs_mobile_location_get_longitude(
const mavlink_message_t* msg)
239 return _MAV_RETURN_float(msg, 4);
250 #if MAVLINK_NEED_BYTE_SWAP
251 slugs_mobile_location->
latitude = mavlink_msg_slugs_mobile_location_get_latitude(msg);
252 slugs_mobile_location->
longitude = mavlink_msg_slugs_mobile_location_get_longitude(msg);
253 slugs_mobile_location->
target = mavlink_msg_slugs_mobile_location_get_target(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
#define MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION
Definition: mavlink_msg_slugs_mobile_location.h:3
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
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 MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION_CRC
Definition: mavlink_msg_slugs_mobile_location.h:15
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float latitude
Mobile Latitude.
Definition: mavlink_msg_slugs_mobile_location.h:7
float longitude
Mobile Longitude.
Definition: mavlink_msg_slugs_mobile_location.h:8
#define MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION_LEN
Definition: mavlink_msg_slugs_mobile_location.h:12
struct __mavlink_slugs_mobile_location_t mavlink_slugs_mobile_location_t
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
Definition: mavlink_msg_slugs_mobile_location.h:5
uint8_t target
The system reporting the action.
Definition: mavlink_msg_slugs_mobile_location.h:9