#include <mavlink_types.h>
Public Attributes | |
uint8_t | compid |
Used by the MAVLink message_xx_send() convenience function. More... | |
uint8_t | mode |
Unused, can be used by user to store the system's mode. More... | |
uint8_t | nav_mode |
Unused, can be used by user to store the system's navigation mode. More... | |
uint8_t | state |
Unused, can be used by user to store the system's state. More... | |
uint8_t | sysid |
Used by the MAVLink message_xx_send() convenience function. More... | |
uint8_t | type |
Unused, can be used by user to store the system's type. More... | |
Definition at line 207 of file include_v0.9/mavlink_types.h.
uint8_t __mavlink_system::compid |
Used by the MAVLink message_xx_send() convenience function.
Definition at line 209 of file include_v0.9/mavlink_types.h.
uint8_t __mavlink_system::mode |
Unused, can be used by user to store the system's mode.
Definition at line 212 of file include_v0.9/mavlink_types.h.
uint8_t __mavlink_system::nav_mode |
Unused, can be used by user to store the system's navigation mode.
Definition at line 213 of file include_v0.9/mavlink_types.h.
uint8_t __mavlink_system::state |
Unused, can be used by user to store the system's state.
Definition at line 211 of file include_v0.9/mavlink_types.h.
uint8_t __mavlink_system::sysid |
Used by the MAVLink message_xx_send() convenience function.
Definition at line 208 of file include_v0.9/mavlink_types.h.
uint8_t __mavlink_system::type |
Unused, can be used by user to store the system's type.
Definition at line 210 of file include_v0.9/mavlink_types.h.