
Go to the source code of this file.
Classes | |
| struct | __mavlink_mission_item_t |
Defines | |
| #define | MAVLINK_MESSAGE_INFO_MISSION_ITEM |
| #define | MAVLINK_MSG_ID_39_CRC 254 |
| #define | MAVLINK_MSG_ID_39_LEN 37 |
| #define | MAVLINK_MSG_ID_MISSION_ITEM 39 |
| #define | MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 |
| #define | MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 |
Typedefs | |
| typedef struct __mavlink_mission_item_t | mavlink_mission_item_t |
Functions | |
| static void | mavlink_msg_mission_item_decode (const mavlink_message_t *msg, mavlink_mission_item_t *mission_item) |
| Decode a mission_item message into a struct. | |
| static uint16_t | mavlink_msg_mission_item_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_mission_item_t *mission_item) |
| Encode a mission_item struct. | |
| static uint16_t | mavlink_msg_mission_item_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_mission_item_t *mission_item) |
| Encode a mission_item struct on a channel. | |
| static uint8_t | mavlink_msg_mission_item_get_autocontinue (const mavlink_message_t *msg) |
| Get field autocontinue from mission_item message. | |
| static uint16_t | mavlink_msg_mission_item_get_command (const mavlink_message_t *msg) |
| Get field command from mission_item message. | |
| static uint8_t | mavlink_msg_mission_item_get_current (const mavlink_message_t *msg) |
| Get field current from mission_item message. | |
| static uint8_t | mavlink_msg_mission_item_get_frame (const mavlink_message_t *msg) |
| Get field frame from mission_item message. | |
| static float | mavlink_msg_mission_item_get_param1 (const mavlink_message_t *msg) |
| Get field param1 from mission_item message. | |
| static float | mavlink_msg_mission_item_get_param2 (const mavlink_message_t *msg) |
| Get field param2 from mission_item message. | |
| static float | mavlink_msg_mission_item_get_param3 (const mavlink_message_t *msg) |
| Get field param3 from mission_item message. | |
| static float | mavlink_msg_mission_item_get_param4 (const mavlink_message_t *msg) |
| Get field param4 from mission_item message. | |
| static uint16_t | mavlink_msg_mission_item_get_seq (const mavlink_message_t *msg) |
| Get field seq from mission_item message. | |
| static uint8_t | mavlink_msg_mission_item_get_target_component (const mavlink_message_t *msg) |
| Get field target_component from mission_item message. | |
| static uint8_t | mavlink_msg_mission_item_get_target_system (const mavlink_message_t *msg) |
| Send a mission_item message. | |
| static float | mavlink_msg_mission_item_get_x (const mavlink_message_t *msg) |
| Get field x from mission_item message. | |
| static float | mavlink_msg_mission_item_get_y (const mavlink_message_t *msg) |
| Get field y from mission_item message. | |
| static float | mavlink_msg_mission_item_get_z (const mavlink_message_t *msg) |
| Get field z from mission_item message. | |
| static uint16_t | mavlink_msg_mission_item_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) |
| Pack a mission_item message. | |
| static uint16_t | mavlink_msg_mission_item_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, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) |
| Pack a mission_item message on a channel. | |
{ \
"MISSION_ITEM", \
14, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \
} \
}
Definition at line 31 of file mavlink_msg_mission_item.h.
| #define MAVLINK_MSG_ID_39_CRC 254 |
Definition at line 27 of file mavlink_msg_mission_item.h.
| #define MAVLINK_MSG_ID_39_LEN 37 |
Definition at line 24 of file mavlink_msg_mission_item.h.
| #define MAVLINK_MSG_ID_MISSION_ITEM 39 |
Definition at line 3 of file mavlink_msg_mission_item.h.
| #define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 |
Definition at line 26 of file mavlink_msg_mission_item.h.
| #define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 |
Definition at line 23 of file mavlink_msg_mission_item.h.
| typedef struct __mavlink_mission_item_t mavlink_mission_item_t |
| static void mavlink_msg_mission_item_decode | ( | const mavlink_message_t * | msg, |
| mavlink_mission_item_t * | mission_item | ||
| ) | [inline, static] |
Decode a mission_item message into a struct.
| msg | The message to decode |
| mission_item | C-struct to decode the message contents into |
Definition at line 501 of file mavlink_msg_mission_item.h.
| static uint16_t mavlink_msg_mission_item_encode | ( | uint8_t | system_id, |
| uint8_t | component_id, | ||
| mavlink_message_t * | msg, | ||
| const mavlink_mission_item_t * | mission_item | ||
| ) | [inline, static] |
Encode a mission_item 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 |
| mission_item | C-struct to read the message contents from |
Definition at line 203 of file mavlink_msg_mission_item.h.
| static uint16_t mavlink_msg_mission_item_encode_chan | ( | uint8_t | system_id, |
| uint8_t | component_id, | ||
| uint8_t | chan, | ||
| mavlink_message_t * | msg, | ||
| const mavlink_mission_item_t * | mission_item | ||
| ) | [inline, static] |
Encode a mission_item 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 |
| mission_item | C-struct to read the message contents from |
Definition at line 217 of file mavlink_msg_mission_item.h.
| static uint8_t mavlink_msg_mission_item_get_autocontinue | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field autocontinue from mission_item message.
Definition at line 420 of file mavlink_msg_mission_item.h.
| static uint16_t mavlink_msg_mission_item_get_command | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field command from mission_item message.
Definition at line 400 of file mavlink_msg_mission_item.h.
| static uint8_t mavlink_msg_mission_item_get_current | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field current from mission_item message.
Definition at line 410 of file mavlink_msg_mission_item.h.
| static uint8_t mavlink_msg_mission_item_get_frame | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field frame from mission_item message.
Definition at line 390 of file mavlink_msg_mission_item.h.
| static float mavlink_msg_mission_item_get_param1 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field param1 from mission_item message.
Definition at line 430 of file mavlink_msg_mission_item.h.
| static float mavlink_msg_mission_item_get_param2 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field param2 from mission_item message.
Definition at line 440 of file mavlink_msg_mission_item.h.
| static float mavlink_msg_mission_item_get_param3 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field param3 from mission_item message.
Definition at line 450 of file mavlink_msg_mission_item.h.
| static float mavlink_msg_mission_item_get_param4 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field param4 from mission_item message.
Definition at line 460 of file mavlink_msg_mission_item.h.
| static uint16_t mavlink_msg_mission_item_get_seq | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field seq from mission_item message.
Definition at line 380 of file mavlink_msg_mission_item.h.
| static uint8_t mavlink_msg_mission_item_get_target_component | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field target_component from mission_item message.
Definition at line 370 of file mavlink_msg_mission_item.h.
| static uint8_t mavlink_msg_mission_item_get_target_system | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a mission_item message.
| chan | MAVLink channel to send the message |
| target_system | System ID |
| target_component | Component ID |
| seq | Sequence |
| frame | The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h |
| command | The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs |
| current | false:0, true:1 |
| autocontinue | autocontinue to next wp |
| param1 | PARAM1, see MAV_CMD enum |
| param2 | PARAM2, see MAV_CMD enum |
| param3 | PARAM3, see MAV_CMD enum |
| param4 | PARAM4, see MAV_CMD enum |
| x | PARAM5 / local: x position, global: latitude |
| y | PARAM6 / y position: global: longitude |
| z | PARAM7 / z position: global: altitude (relative or absolute, depending on frame. Get field target_system from mission_item message |
Definition at line 360 of file mavlink_msg_mission_item.h.
| static float mavlink_msg_mission_item_get_x | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field x from mission_item message.
Definition at line 470 of file mavlink_msg_mission_item.h.
| static float mavlink_msg_mission_item_get_y | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field y from mission_item message.
Definition at line 480 of file mavlink_msg_mission_item.h.
| static float mavlink_msg_mission_item_get_z | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field z from mission_item message.
Definition at line 490 of file mavlink_msg_mission_item.h.
| static uint16_t mavlink_msg_mission_item_pack | ( | uint8_t | system_id, |
| uint8_t | component_id, | ||
| mavlink_message_t * | msg, | ||
| uint8_t | target_system, | ||
| uint8_t | target_component, | ||
| uint16_t | seq, | ||
| uint8_t | frame, | ||
| uint16_t | command, | ||
| uint8_t | current, | ||
| uint8_t | autocontinue, | ||
| float | param1, | ||
| float | param2, | ||
| float | param3, | ||
| float | param4, | ||
| float | x, | ||
| float | y, | ||
| float | z | ||
| ) | [inline, static] |
Pack a mission_item 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 |
| seq | Sequence |
| frame | The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h |
| command | The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs |
| current | false:0, true:1 |
| autocontinue | autocontinue to next wp |
| param1 | PARAM1, see MAV_CMD enum |
| param2 | PARAM2, see MAV_CMD enum |
| param3 | PARAM3, see MAV_CMD enum |
| param4 | PARAM4, see MAV_CMD enum |
| x | PARAM5 / local: x position, global: latitude |
| y | PARAM6 / y position: global: longitude |
| z | PARAM7 / z position: global: altitude (relative or absolute, depending on frame. |
Definition at line 74 of file mavlink_msg_mission_item.h.
| static uint16_t mavlink_msg_mission_item_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, | ||
| uint16_t | seq, | ||
| uint8_t | frame, | ||
| uint16_t | command, | ||
| uint8_t | current, | ||
| uint8_t | autocontinue, | ||
| float | param1, | ||
| float | param2, | ||
| float | param3, | ||
| float | param4, | ||
| float | x, | ||
| float | y, | ||
| float | z | ||
| ) | [inline, static] |
Pack a mission_item 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 |
| seq | Sequence |
| frame | The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h |
| command | The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs |
| current | false:0, true:1 |
| autocontinue | autocontinue to next wp |
| param1 | PARAM1, see MAV_CMD enum |
| param2 | PARAM2, see MAV_CMD enum |
| param3 | PARAM3, see MAV_CMD enum |
| param4 | PARAM4, see MAV_CMD enum |
| x | PARAM5 / local: x position, global: latitude |
| y | PARAM6 / y position: global: longitude |
| z | PARAM7 / z position: global: altitude (relative or absolute, depending on frame. |
Definition at line 145 of file mavlink_msg_mission_item.h.