Classes | Macros | Typedefs | Functions
mavlink_msg_safety_allowed_area.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_safety_allowed_area_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA
 
#define MAVLINK_MSG_ID_55_CRC   3
 
#define MAVLINK_MSG_ID_55_LEN   25
 
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA   55
 
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC   3
 
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN   25
 

Typedefs

typedef struct __mavlink_safety_allowed_area_t mavlink_safety_allowed_area_t
 

Functions

static void mavlink_msg_safety_allowed_area_decode (const mavlink_message_t *msg, mavlink_safety_allowed_area_t *safety_allowed_area)
 Decode a safety_allowed_area message into a struct. More...
 
static 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)
 Encode a safety_allowed_area struct. More...
 
static 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)
 Encode a safety_allowed_area struct on a channel. More...
 
static uint8_t mavlink_msg_safety_allowed_area_get_frame (const mavlink_message_t *msg)
 Send a safety_allowed_area message. More...
 
static float mavlink_msg_safety_allowed_area_get_p1x (const mavlink_message_t *msg)
 Get field p1x from safety_allowed_area message. More...
 
static float mavlink_msg_safety_allowed_area_get_p1y (const mavlink_message_t *msg)
 Get field p1y from safety_allowed_area message. More...
 
static float mavlink_msg_safety_allowed_area_get_p1z (const mavlink_message_t *msg)
 Get field p1z from safety_allowed_area message. More...
 
static float mavlink_msg_safety_allowed_area_get_p2x (const mavlink_message_t *msg)
 Get field p2x from safety_allowed_area message. More...
 
static float mavlink_msg_safety_allowed_area_get_p2y (const mavlink_message_t *msg)
 Get field p2y from safety_allowed_area message. More...
 
static float mavlink_msg_safety_allowed_area_get_p2z (const mavlink_message_t *msg)
 Get field p2z from safety_allowed_area message. More...
 
static uint16_t mavlink_msg_safety_allowed_area_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
 Pack a safety_allowed_area message. More...
 
static uint16_t mavlink_msg_safety_allowed_area_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
 Pack a safety_allowed_area message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA
Value:
{ \
"SAFETY_ALLOWED_AREA", \
7, \
{ { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \
{ "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \
{ "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \
{ "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \
{ "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \
{ "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_safety_allowed_area.h.

#define MAVLINK_MSG_ID_55_CRC   3

Definition at line 20 of file mavlink_msg_safety_allowed_area.h.

#define MAVLINK_MSG_ID_55_LEN   25

Definition at line 17 of file mavlink_msg_safety_allowed_area.h.

#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA   55

Definition at line 3 of file mavlink_msg_safety_allowed_area.h.

#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC   3

Definition at line 19 of file mavlink_msg_safety_allowed_area.h.

#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN   25

Definition at line 16 of file mavlink_msg_safety_allowed_area.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_safety_allowed_area_decode ( const mavlink_message_t *  msg,
mavlink_safety_allowed_area_t safety_allowed_area 
)
inlinestatic

Decode a safety_allowed_area message into a struct.

Parameters
msgThe message to decode
safety_allowed_areaC-struct to decode the message contents into

Definition at line 340 of file mavlink_msg_safety_allowed_area.h.

static 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 
)
inlinestatic

Encode a safety_allowed_area struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
safety_allowed_areaC-struct to read the message contents from

Definition at line 147 of file mavlink_msg_safety_allowed_area.h.

static 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 
)
inlinestatic

Encode a safety_allowed_area struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
safety_allowed_areaC-struct to read the message contents from

Definition at line 161 of file mavlink_msg_safety_allowed_area.h.

static uint8_t mavlink_msg_safety_allowed_area_get_frame ( const mavlink_message_t *  msg)
inlinestatic

Send a safety_allowed_area message.

Parameters
chanMAVLink channel to send the message
frameCoordinate 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.
p1xx position 1 / Latitude 1
p1yy position 1 / Longitude 1
p1zz position 1 / Altitude 1
p2xx position 2 / Latitude 2
p2yy position 2 / Longitude 2
p2zz position 2 / Altitude 2 Get field frame from safety_allowed_area message
Returns
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.

Definition at line 269 of file mavlink_msg_safety_allowed_area.h.

static float mavlink_msg_safety_allowed_area_get_p1x ( const mavlink_message_t *  msg)
inlinestatic

Get field p1x from safety_allowed_area message.

Returns
x position 1 / Latitude 1

Definition at line 279 of file mavlink_msg_safety_allowed_area.h.

static float mavlink_msg_safety_allowed_area_get_p1y ( const mavlink_message_t *  msg)
inlinestatic

Get field p1y from safety_allowed_area message.

Returns
y position 1 / Longitude 1

Definition at line 289 of file mavlink_msg_safety_allowed_area.h.

static float mavlink_msg_safety_allowed_area_get_p1z ( const mavlink_message_t *  msg)
inlinestatic

Get field p1z from safety_allowed_area message.

Returns
z position 1 / Altitude 1

Definition at line 299 of file mavlink_msg_safety_allowed_area.h.

static float mavlink_msg_safety_allowed_area_get_p2x ( const mavlink_message_t *  msg)
inlinestatic

Get field p2x from safety_allowed_area message.

Returns
x position 2 / Latitude 2

Definition at line 309 of file mavlink_msg_safety_allowed_area.h.

static float mavlink_msg_safety_allowed_area_get_p2y ( const mavlink_message_t *  msg)
inlinestatic

Get field p2y from safety_allowed_area message.

Returns
y position 2 / Longitude 2

Definition at line 319 of file mavlink_msg_safety_allowed_area.h.

static float mavlink_msg_safety_allowed_area_get_p2z ( const mavlink_message_t *  msg)
inlinestatic

Get field p2z from safety_allowed_area message.

Returns
z position 2 / Altitude 2

Definition at line 329 of file mavlink_msg_safety_allowed_area.h.

static uint16_t mavlink_msg_safety_allowed_area_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  frame,
float  p1x,
float  p1y,
float  p1z,
float  p2x,
float  p2y,
float  p2z 
)
inlinestatic

Pack a safety_allowed_area message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
frameCoordinate 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.
p1xx position 1 / Latitude 1
p1yy position 1 / Longitude 1
p1zz position 1 / Altitude 1
p2xx position 2 / Latitude 2
p2yy position 2 / Longitude 2
p2zz position 2 / Altitude 2
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_safety_allowed_area.h.

static uint16_t mavlink_msg_safety_allowed_area_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  frame,
float  p1x,
float  p1y,
float  p1z,
float  p2x,
float  p2y,
float  p2z 
)
inlinestatic

Pack a safety_allowed_area message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
frameCoordinate 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.
p1xx position 1 / Latitude 1
p1yy position 1 / Longitude 1
p1zz position 1 / Altitude 1
p2xx position 2 / Latitude 2
p2yy position 2 / Longitude 2
p2zz position 2 / Altitude 2
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_safety_allowed_area.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51