
Go to the source code of this file.
| Classes | |
| struct | __mavlink_rosflight_status_t | 
| Macros | |
| #define | MAVLINK_MESSAGE_INFO_ROSFLIGHT_STATUS | 
| #define | MAVLINK_MSG_ID_191_CRC 183 | 
| #define | MAVLINK_MSG_ID_191_LEN 10 | 
| #define | MAVLINK_MSG_ID_ROSFLIGHT_STATUS 191 | 
| #define | MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC 183 | 
| #define | MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN 10 | 
| Typedefs | |
| typedef struct __mavlink_rosflight_status_t | mavlink_rosflight_status_t | 
| Functions | |
| static void | mavlink_msg_rosflight_status_decode (const mavlink_message_t *msg, mavlink_rosflight_status_t *rosflight_status) | 
| Decode a rosflight_status message into a struct.  More... | |
| static uint16_t | mavlink_msg_rosflight_status_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_status_t *rosflight_status) | 
| Encode a rosflight_status struct.  More... | |
| static uint16_t | mavlink_msg_rosflight_status_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_status_t *rosflight_status) | 
| Encode a rosflight_status struct on a channel.  More... | |
| static uint8_t | mavlink_msg_rosflight_status_get_armed (const mavlink_message_t *msg) | 
| Send a rosflight_status message.  More... | |
| static uint8_t | mavlink_msg_rosflight_status_get_control_mode (const mavlink_message_t *msg) | 
| Get field control_mode from rosflight_status message.  More... | |
| static uint8_t | mavlink_msg_rosflight_status_get_error_code (const mavlink_message_t *msg) | 
| Get field error_code from rosflight_status message.  More... | |
| static uint8_t | mavlink_msg_rosflight_status_get_failsafe (const mavlink_message_t *msg) | 
| Get field failsafe from rosflight_status message.  More... | |
| static int16_t | mavlink_msg_rosflight_status_get_loop_time_us (const mavlink_message_t *msg) | 
| Get field loop_time_us from rosflight_status message.  More... | |
| static int16_t | mavlink_msg_rosflight_status_get_num_errors (const mavlink_message_t *msg) | 
| Get field num_errors from rosflight_status message.  More... | |
| static uint8_t | mavlink_msg_rosflight_status_get_offboard (const mavlink_message_t *msg) | 
| Get field offboard from rosflight_status message.  More... | |
| static uint8_t | mavlink_msg_rosflight_status_get_rc_override (const mavlink_message_t *msg) | 
| Get field rc_override from rosflight_status message.  More... | |
| static uint16_t | mavlink_msg_rosflight_status_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) | 
| Pack a rosflight_status message.  More... | |
| static uint16_t | mavlink_msg_rosflight_status_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) | 
| Pack a rosflight_status message on a channel.  More... | |
| #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_STATUS | 
Definition at line 25 of file mavlink_msg_rosflight_status.h.
| #define MAVLINK_MSG_ID_191_CRC 183 | 
Definition at line 21 of file mavlink_msg_rosflight_status.h.
| #define MAVLINK_MSG_ID_191_LEN 10 | 
Definition at line 18 of file mavlink_msg_rosflight_status.h.
| #define MAVLINK_MSG_ID_ROSFLIGHT_STATUS 191 | 
Definition at line 3 of file mavlink_msg_rosflight_status.h.
| #define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC 183 | 
Definition at line 20 of file mavlink_msg_rosflight_status.h.
| #define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN 10 | 
Definition at line 17 of file mavlink_msg_rosflight_status.h.
| typedef struct __mavlink_rosflight_status_t mavlink_rosflight_status_t | 
| 
 | inlinestatic | 
Decode a rosflight_status message into a struct.
| msg | The message to decode | 
| rosflight_status | C-struct to decode the message contents into | 
Definition at line 363 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Encode a rosflight_status 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 | 
| rosflight_status | C-struct to read the message contents from | 
Definition at line 155 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Encode a rosflight_status 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 | 
| rosflight_status | C-struct to read the message contents from | 
Definition at line 169 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Send a rosflight_status message.
| chan | MAVLink channel to send the message | 
| armed | |
| failsafe | |
| rc_override | |
| offboard | |
| error_code | |
| control_mode | |
| num_errors | |
| loop_time_us | Get field armed from rosflight_status message | 
Definition at line 282 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Get field control_mode from rosflight_status message.
Definition at line 332 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Get field error_code from rosflight_status message.
Definition at line 322 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Get field failsafe from rosflight_status message.
Definition at line 292 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Get field loop_time_us from rosflight_status message.
Definition at line 352 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Get field num_errors from rosflight_status message.
Definition at line 342 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Get field offboard from rosflight_status message.
Definition at line 312 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Get field rc_override from rosflight_status message.
Definition at line 302 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Pack a rosflight_status 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 | 
| armed | |
| failsafe | |
| rc_override | |
| offboard | |
| error_code | |
| control_mode | |
| num_errors | |
| loop_time_us | 
Definition at line 56 of file mavlink_msg_rosflight_status.h.
| 
 | inlinestatic | 
Pack a rosflight_status 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 | 
| armed | |
| failsafe | |
| rc_override | |
| offboard | |
| error_code | |
| control_mode | |
| num_errors | |
| loop_time_us | 
Definition at line 109 of file mavlink_msg_rosflight_status.h.