
Go to the source code of this file.
Classes | |
| struct | __mavlink_safety_set_allowed_area_t |
Defines | |
| #define | MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA |
| #define | MAVLINK_MSG_ID_54_CRC 15 |
| #define | MAVLINK_MSG_ID_54_LEN 27 |
| #define | MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 |
| #define | MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 |
| #define | MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 |
Typedefs | |
| typedef struct __mavlink_safety_set_allowed_area_t | mavlink_safety_set_allowed_area_t |
Functions | |
| static void | mavlink_msg_safety_set_allowed_area_decode (const mavlink_message_t *msg, mavlink_safety_set_allowed_area_t *safety_set_allowed_area) |
| Decode a safety_set_allowed_area message into a struct. | |
| static uint16_t | mavlink_msg_safety_set_allowed_area_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_safety_set_allowed_area_t *safety_set_allowed_area) |
| Encode a safety_set_allowed_area struct. | |
| static uint16_t | mavlink_msg_safety_set_allowed_area_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_safety_set_allowed_area_t *safety_set_allowed_area) |
| Encode a safety_set_allowed_area struct on a channel. | |
| static uint8_t | mavlink_msg_safety_set_allowed_area_get_frame (const mavlink_message_t *msg) |
| Get field frame from safety_set_allowed_area message. | |
| static float | mavlink_msg_safety_set_allowed_area_get_p1x (const mavlink_message_t *msg) |
| Get field p1x from safety_set_allowed_area message. | |
| static float | mavlink_msg_safety_set_allowed_area_get_p1y (const mavlink_message_t *msg) |
| Get field p1y from safety_set_allowed_area message. | |
| static float | mavlink_msg_safety_set_allowed_area_get_p1z (const mavlink_message_t *msg) |
| Get field p1z from safety_set_allowed_area message. | |
| static float | mavlink_msg_safety_set_allowed_area_get_p2x (const mavlink_message_t *msg) |
| Get field p2x from safety_set_allowed_area message. | |
| static float | mavlink_msg_safety_set_allowed_area_get_p2y (const mavlink_message_t *msg) |
| Get field p2y from safety_set_allowed_area message. | |
| static float | mavlink_msg_safety_set_allowed_area_get_p2z (const mavlink_message_t *msg) |
| Get field p2z from safety_set_allowed_area message. | |
| static uint8_t | mavlink_msg_safety_set_allowed_area_get_target_component (const mavlink_message_t *msg) |
| Get field target_component from safety_set_allowed_area message. | |
| static uint8_t | mavlink_msg_safety_set_allowed_area_get_target_system (const mavlink_message_t *msg) |
| Send a safety_set_allowed_area message. | |
| static uint16_t | mavlink_msg_safety_set_allowed_area_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) |
| Pack a safety_set_allowed_area message. | |
| static uint16_t | mavlink_msg_safety_set_allowed_area_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) |
| Pack a safety_set_allowed_area message on a channel. | |
{ \
"SAFETY_SET_ALLOWED_AREA", \
9, \
{ { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \
{ "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \
{ "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \
{ "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \
{ "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \
{ "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \
} \
}
Definition at line 26 of file mavlink_msg_safety_set_allowed_area.h.
| #define MAVLINK_MSG_ID_54_CRC 15 |
Definition at line 22 of file mavlink_msg_safety_set_allowed_area.h.
| #define MAVLINK_MSG_ID_54_LEN 27 |
Definition at line 19 of file mavlink_msg_safety_set_allowed_area.h.
| #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 |
Definition at line 3 of file mavlink_msg_safety_set_allowed_area.h.
| #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 |
Definition at line 21 of file mavlink_msg_safety_set_allowed_area.h.
| #define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 |
Definition at line 18 of file mavlink_msg_safety_set_allowed_area.h.
| static void mavlink_msg_safety_set_allowed_area_decode | ( | const mavlink_message_t * | msg, |
| mavlink_safety_set_allowed_area_t * | safety_set_allowed_area | ||
| ) | [inline, static] |
Decode a safety_set_allowed_area message into a struct.
| msg | The message to decode |
| safety_set_allowed_area | C-struct to decode the message contents into |
Definition at line 386 of file mavlink_msg_safety_set_allowed_area.h.
| static uint16_t mavlink_msg_safety_set_allowed_area_encode | ( | uint8_t | system_id, |
| uint8_t | component_id, | ||
| mavlink_message_t * | msg, | ||
| const mavlink_safety_set_allowed_area_t * | safety_set_allowed_area | ||
| ) | [inline, static] |
Encode a safety_set_allowed_area struct.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| msg | The MAVLink message to compress the data into |
| safety_set_allowed_area | C-struct to read the message contents from |
Definition at line 163 of file mavlink_msg_safety_set_allowed_area.h.
| static uint16_t mavlink_msg_safety_set_allowed_area_encode_chan | ( | uint8_t | system_id, |
| uint8_t | component_id, | ||
| uint8_t | chan, | ||
| mavlink_message_t * | msg, | ||
| const mavlink_safety_set_allowed_area_t * | safety_set_allowed_area | ||
| ) | [inline, static] |
Encode a safety_set_allowed_area struct on a channel.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| chan | The MAVLink channel this message will be sent over |
| msg | The MAVLink message to compress the data into |
| safety_set_allowed_area | C-struct to read the message contents from |
Definition at line 177 of file mavlink_msg_safety_set_allowed_area.h.
| static uint8_t mavlink_msg_safety_set_allowed_area_get_frame | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field frame from safety_set_allowed_area message.
Definition at line 315 of file mavlink_msg_safety_set_allowed_area.h.
| static float mavlink_msg_safety_set_allowed_area_get_p1x | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field p1x from safety_set_allowed_area message.
Definition at line 325 of file mavlink_msg_safety_set_allowed_area.h.
| static float mavlink_msg_safety_set_allowed_area_get_p1y | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field p1y from safety_set_allowed_area message.
Definition at line 335 of file mavlink_msg_safety_set_allowed_area.h.
| static float mavlink_msg_safety_set_allowed_area_get_p1z | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field p1z from safety_set_allowed_area message.
Definition at line 345 of file mavlink_msg_safety_set_allowed_area.h.
| static float mavlink_msg_safety_set_allowed_area_get_p2x | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field p2x from safety_set_allowed_area message.
Definition at line 355 of file mavlink_msg_safety_set_allowed_area.h.
| static float mavlink_msg_safety_set_allowed_area_get_p2y | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field p2y from safety_set_allowed_area message.
Definition at line 365 of file mavlink_msg_safety_set_allowed_area.h.
| static float mavlink_msg_safety_set_allowed_area_get_p2z | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field p2z from safety_set_allowed_area message.
Definition at line 375 of file mavlink_msg_safety_set_allowed_area.h.
| static uint8_t mavlink_msg_safety_set_allowed_area_get_target_component | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field target_component from safety_set_allowed_area message.
Definition at line 305 of file mavlink_msg_safety_set_allowed_area.h.
| static uint8_t mavlink_msg_safety_set_allowed_area_get_target_system | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a safety_set_allowed_area message.
| chan | MAVLink channel to send the message |
| target_system | System ID |
| target_component | Component ID |
| frame | 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. |
| p1x | x position 1 / Latitude 1 |
| p1y | y position 1 / Longitude 1 |
| p1z | z position 1 / Altitude 1 |
| p2x | x position 2 / Latitude 2 |
| p2y | y position 2 / Longitude 2 |
| p2z | z position 2 / Altitude 2 Get field target_system from safety_set_allowed_area message |
Definition at line 295 of file mavlink_msg_safety_set_allowed_area.h.
| static uint16_t mavlink_msg_safety_set_allowed_area_pack | ( | uint8_t | system_id, |
| uint8_t | component_id, | ||
| mavlink_message_t * | msg, | ||
| uint8_t | target_system, | ||
| uint8_t | target_component, | ||
| uint8_t | frame, | ||
| float | p1x, | ||
| float | p1y, | ||
| float | p1z, | ||
| float | p2x, | ||
| float | p2y, | ||
| float | p2z | ||
| ) | [inline, static] |
Pack a safety_set_allowed_area message.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| msg | The MAVLink message to compress the data into |
| target_system | System ID |
| target_component | Component ID |
| frame | 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. |
| p1x | x position 1 / Latitude 1 |
| p1y | y position 1 / Longitude 1 |
| p1z | z position 1 / Altitude 1 |
| p2x | x position 2 / Latitude 2 |
| p2y | y position 2 / Longitude 2 |
| p2z | z position 2 / Altitude 2 |
Definition at line 59 of file mavlink_msg_safety_set_allowed_area.h.
| static uint16_t mavlink_msg_safety_set_allowed_area_pack_chan | ( | uint8_t | system_id, |
| uint8_t | component_id, | ||
| uint8_t | chan, | ||
| mavlink_message_t * | msg, | ||
| uint8_t | target_system, | ||
| uint8_t | target_component, | ||
| uint8_t | frame, | ||
| float | p1x, | ||
| float | p1y, | ||
| float | p1z, | ||
| float | p2x, | ||
| float | p2y, | ||
| float | p2z | ||
| ) | [inline, static] |
Pack a safety_set_allowed_area message on a channel.
| system_id | ID of this system |
| component_id | ID of this component (e.g. 200 for IMU) |
| chan | The MAVLink channel this message will be sent over |
| msg | The MAVLink message to compress the data into |
| target_system | System ID |
| target_component | Component ID |
| frame | 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. |
| p1x | x position 1 / Latitude 1 |
| p1y | y position 1 / Longitude 1 |
| p1z | z position 1 / Altitude 1 |
| p2x | x position 2 / Latitude 2 |
| p2y | y position 2 / Longitude 2 |
| p2z | z position 2 / Altitude 2 |
Definition at line 115 of file mavlink_msg_safety_set_allowed_area.h.