Go to the source code of this file.
|  | 
| static void | mavlink_msg_set_mode_decode (const mavlink_message_t *msg, mavlink_set_mode_t *set_mode) | 
|  | Decode a set_mode message into a struct.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_set_mode_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_mode_t *set_mode) | 
|  | Encode a set_mode struct.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_set_mode_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_mode_t *set_mode) | 
|  | Encode a set_mode struct on a channel.  More... 
 | 
|  | 
| static uint8_t | mavlink_msg_set_mode_get_base_mode (const mavlink_message_t *msg) | 
|  | Get field base_mode from set_mode message.  More... 
 | 
|  | 
| static uint32_t | mavlink_msg_set_mode_get_custom_mode (const mavlink_message_t *msg) | 
|  | Get field custom_mode from set_mode message.  More... 
 | 
|  | 
| static uint8_t | mavlink_msg_set_mode_get_target_system (const mavlink_message_t *msg) | 
|  | Send a set_mode message.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_set_mode_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) | 
|  | Pack a set_mode message.  More... 
 | 
|  | 
| static uint16_t | mavlink_msg_set_mode_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) | 
|  | Pack a set_mode message on a channel.  More... 
 | 
|  | 
      
        
          | #define MAVLINK_MESSAGE_INFO_SET_MODE | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_11_CRC   89 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_11_LEN   6 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_SET_MODE   11 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_SET_MODE_CRC   89 | 
      
 
 
      
        
          | #define MAVLINK_MSG_ID_SET_MODE_LEN   6 | 
      
 
 
  
  | 
        
          | static void mavlink_msg_set_mode_decode | ( | const mavlink_message_t * | msg, |  
          |  |  | mavlink_set_mode_t * | set_mode |  
          |  | ) |  |  |  | inlinestatic | 
 
Decode a set_mode message into a struct. 
- Parameters
- 
  
    | msg | The message to decode |  | set_mode | C-struct to decode the message contents into |  
 
Definition at line 248 of file mavlink_msg_set_mode.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_set_mode_encode | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | const mavlink_set_mode_t * | set_mode |  
          |  | ) |  |  |  | inlinestatic | 
 
Encode a set_mode 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 |  | set_mode | C-struct to read the message contents from |  
 
Definition at line 115 of file mavlink_msg_set_mode.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_set_mode_encode_chan | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | uint8_t | chan, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | const mavlink_set_mode_t * | set_mode |  
          |  | ) |  |  |  | inlinestatic | 
 
Encode a set_mode 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 |  | set_mode | C-struct to read the message contents from |  
 
Definition at line 129 of file mavlink_msg_set_mode.h.
 
 
  
  | 
        
          | static uint8_t mavlink_msg_set_mode_get_base_mode | ( | const mavlink_message_t * | msg | ) |  |  | inlinestatic | 
 
 
  
  | 
        
          | static uint32_t mavlink_msg_set_mode_get_custom_mode | ( | const mavlink_message_t * | msg | ) |  |  | inlinestatic | 
 
Get field custom_mode from set_mode message. 
- Returns
- The new autopilot-specific mode. This field can be ignored by an autopilot. 
Definition at line 237 of file mavlink_msg_set_mode.h.
 
 
  
  | 
        
          | static uint8_t mavlink_msg_set_mode_get_target_system | ( | const mavlink_message_t * | msg | ) |  |  | inlinestatic | 
 
Send a set_mode message. 
- Parameters
- 
  
    | chan | MAVLink channel to send the message |  | target_system | The system setting the mode |  | base_mode | The new base mode |  | custom_mode | The new autopilot-specific mode. This field can be ignored by an autopilot. Get field target_system from set_mode message |  
 
- Returns
- The system setting the mode 
Definition at line 217 of file mavlink_msg_set_mode.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_set_mode_pack | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | uint8_t | target_system, |  
          |  |  | uint8_t | base_mode, |  
          |  |  | uint32_t | custom_mode |  
          |  | ) |  |  |  | inlinestatic | 
 
Pack a set_mode 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 |  | target_system | The system setting the mode |  | base_mode | The new base mode |  | custom_mode | The new autopilot-specific mode. This field can be ignored by an autopilot. |  
 
- Returns
- length of the message in bytes (excluding serial stream start sign) 
Definition at line 41 of file mavlink_msg_set_mode.h.
 
 
  
  | 
        
          | static uint16_t mavlink_msg_set_mode_pack_chan | ( | uint8_t | system_id, |  
          |  |  | uint8_t | component_id, |  
          |  |  | uint8_t | chan, |  
          |  |  | mavlink_message_t * | msg, |  
          |  |  | uint8_t | target_system, |  
          |  |  | uint8_t | base_mode, |  
          |  |  | uint32_t | custom_mode |  
          |  | ) |  |  |  | inlinestatic | 
 
Pack a set_mode 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 |  | target_system | The system setting the mode |  | base_mode | The new base mode |  | custom_mode | The new autopilot-specific mode. This field can be ignored by an autopilot. |  
 
- Returns
- length of the message in bytes (excluding serial stream start sign) 
Definition at line 79 of file mavlink_msg_set_mode.h.