3 #define MAVLINK_MSG_ID_ISR_LOCATION 189
16 #define MAVLINK_MSG_ID_ISR_LOCATION_LEN 16
17 #define MAVLINK_MSG_ID_189_LEN 16
19 #define MAVLINK_MSG_ID_ISR_LOCATION_CRC 246
20 #define MAVLINK_MSG_ID_189_CRC 246
24 #define MAVLINK_MESSAGE_INFO_ISR_LOCATION { \
27 { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_isr_location_t, latitude) }, \
28 { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_isr_location_t, longitude) }, \
29 { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_isr_location_t, height) }, \
30 { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_isr_location_t, target) }, \
31 { "option1", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_isr_location_t, option1) }, \
32 { "option2", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_isr_location_t, option2) }, \
33 { "option3", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_isr_location_t, option3) }, \
53 static inline uint16_t mavlink_msg_isr_location_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54 uint8_t target,
float latitude,
float longitude,
float height, uint8_t option1, uint8_t option2, uint8_t option3)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103 static inline uint16_t mavlink_msg_isr_location_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104 mavlink_message_t* msg,
105 uint8_t target,
float latitude,
float longitude,
float height,uint8_t option1,uint8_t option2,uint8_t option3)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 #if MAVLINK_CRC_EXTRA
147 static inline uint16_t mavlink_msg_isr_location_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_isr_location_t* isr_location)
161 static inline uint16_t mavlink_msg_isr_location_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_isr_location_t* isr_location)
163 return mavlink_msg_isr_location_pack_chan(system_id, component_id, chan, msg, isr_location->
target, isr_location->
latitude, isr_location->
longitude, isr_location->
height, isr_location->
option1, isr_location->
option2, isr_location->
option3);
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180 static inline void mavlink_msg_isr_location_send(
mavlink_channel_t chan, uint8_t target,
float latitude,
float longitude,
float height, uint8_t option1, uint8_t option2, uint8_t option3)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
192 #if MAVLINK_CRC_EXTRA
207 #if MAVLINK_CRC_EXTRA
215 #if MAVLINK_MSG_ID_ISR_LOCATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
223 static inline void mavlink_msg_isr_location_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t target,
float latitude,
float longitude,
float height, uint8_t option1, uint8_t option2, uint8_t option3)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226 char *buf = (
char *)msgbuf;
235 #if MAVLINK_CRC_EXTRA
250 #if MAVLINK_CRC_EXTRA
269 static inline uint8_t mavlink_msg_isr_location_get_target(
const mavlink_message_t* msg)
279 static inline float mavlink_msg_isr_location_get_latitude(
const mavlink_message_t* msg)
281 return _MAV_RETURN_float(msg, 0);
289 static inline float mavlink_msg_isr_location_get_longitude(
const mavlink_message_t* msg)
291 return _MAV_RETURN_float(msg, 4);
299 static inline float mavlink_msg_isr_location_get_height(
const mavlink_message_t* msg)
301 return _MAV_RETURN_float(msg, 8);
309 static inline uint8_t mavlink_msg_isr_location_get_option1(
const mavlink_message_t* msg)
319 static inline uint8_t mavlink_msg_isr_location_get_option2(
const mavlink_message_t* msg)
329 static inline uint8_t mavlink_msg_isr_location_get_option3(
const mavlink_message_t* msg)
340 static inline void mavlink_msg_isr_location_decode(
const mavlink_message_t* msg,
mavlink_isr_location_t* isr_location)
342 #if MAVLINK_NEED_BYTE_SWAP
343 isr_location->
latitude = mavlink_msg_isr_location_get_latitude(msg);
344 isr_location->
longitude = mavlink_msg_isr_location_get_longitude(msg);
345 isr_location->
height = mavlink_msg_isr_location_get_height(msg);
346 isr_location->
target = mavlink_msg_isr_location_get_target(msg);
347 isr_location->
option1 = mavlink_msg_isr_location_get_option1(msg);
348 isr_location->
option2 = mavlink_msg_isr_location_get_option2(msg);
349 isr_location->
option3 = mavlink_msg_isr_location_get_option3(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float longitude
ISR Longitude.
Definition: mavlink_msg_isr_location.h:8
#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 _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 MAVLINK_MSG_ID_ISR_LOCATION
Definition: mavlink_msg_isr_location.h:3
uint8_t option3
Option 3.
Definition: mavlink_msg_isr_location.h:13
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float height
ISR Height.
Definition: mavlink_msg_isr_location.h:9
float latitude
ISR Latitude.
Definition: mavlink_msg_isr_location.h:7
uint8_t target
The system reporting the action.
Definition: mavlink_msg_isr_location.h:10
Definition: mavlink_msg_isr_location.h:5
uint8_t option2
Option 2.
Definition: mavlink_msg_isr_location.h:12
#define MAVLINK_MSG_ID_ISR_LOCATION_LEN
Definition: mavlink_msg_isr_location.h:16
#define MAVLINK_MSG_ID_ISR_LOCATION_CRC
Definition: mavlink_msg_isr_location.h:19
uint8_t option1
Option 1.
Definition: mavlink_msg_isr_location.h:11
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
struct __mavlink_isr_location_t mavlink_isr_location_t