Go to the source code of this file.
|  | 
| static void | mavlink_msg_mission_item_reached_decode (const mavlink_message_t *msg, mavlink_mission_item_reached_t *mission_item_reached) | 
|  | Decode a mission_item_reached message into a struct.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_mission_item_reached_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_mission_item_reached_t *mission_item_reached) | 
|  | Encode a mission_item_reached struct.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_mission_item_reached_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_mission_item_reached_t *mission_item_reached) | 
|  | Encode a mission_item_reached struct on a channel.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_mission_item_reached_get_seq (const mavlink_message_t *msg) | 
|  | Send a mission_item_reached message.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_mission_item_reached_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint16_t seq) | 
|  | Pack a mission_item_reached message.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_mission_item_reached_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint16_t seq) | 
|  | Pack a mission_item_reached message on a channel.  More... 
 | 
|  | 
      
        
          | #define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_46_CRC   11 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_46_LEN   2 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_MISSION_ITEM_REACHED   46 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC   11 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN   2 | 
      
 
 
Decode a mission_item_reached message into a struct. 
- Parameters
- 
  
    | msg | The message to decode |  | mission_item_reached | C-struct to decode the message contents into |  
 
Definition at line 202 of file mavlink_msg_mission_item_reached.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_mission_item_reached_encode | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | const mavlink_mission_item_reached_t * | mission_item_reached |  
          |  | ) |  |  |  | inlinestatic | 
 
Encode a mission_item_reached struct. 
- Parameters
- 
  
    | 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_reached | C-struct to read the message contents from |  
 
Definition at line 99 of file mavlink_msg_mission_item_reached.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_mission_item_reached_encode_chan | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | uint8_t | chan, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | const mavlink_mission_item_reached_t * | mission_item_reached |  
          |  | ) |  |  |  | inlinestatic | 
 
Encode a mission_item_reached struct on a channel. 
- Parameters
- 
  
    | 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_reached | C-struct to read the message contents from |  
 
Definition at line 113 of file mavlink_msg_mission_item_reached.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_mission_item_reached_get_seq | ( | const mavlink_message_t * | msg | ) |  |  | inlinestatic | 
 
Send a mission_item_reached message. 
- Parameters
- 
  
    | chan | MAVLink channel to send the message |  | seq | Sequence Get field seq from mission_item_reached message |  
 
- Returns
- Sequence 
Definition at line 191 of file mavlink_msg_mission_item_reached.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_mission_item_reached_pack | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | uint16_t | seq |  
          |  | ) |  |  |  | inlinestatic | 
 
Pack a mission_item_reached message. 
- Parameters
- 
  
    | 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 |  | seq | Sequence |  
 
- Returns
- length of the message in bytes (excluding serial stream start sign) 
Definition at line 35 of file mavlink_msg_mission_item_reached.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_mission_item_reached_pack_chan | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | uint8_t | chan, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | uint16_t | seq |  
          |  | ) |  |  |  | inlinestatic | 
 
Pack a mission_item_reached message on a channel. 
- Parameters
- 
  
    | 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 |  | seq | Sequence |  
 
- Returns
- length of the message in bytes (excluding serial stream start sign) 
Definition at line 67 of file mavlink_msg_mission_item_reached.h.