|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <px4_custom_mode.h>
Public Attributes | |
| struct { | |
| uint16_t reserved | |
| uint8_t main_mode | |
| uint8_t sub_mode | |
| }; | |
| uint32_t | data |
| float | data_float |
| struct { | |
| uint16_t reserved_hl | |
| uint16_t custom_mode_hl | |
| }; | |
Definition at line 74 of file px4_custom_mode.h.
| struct { ... } |
| struct { ... } |
| uint16_t px4_custom_mode::custom_mode_hl |
Definition at line 84 of file px4_custom_mode.h.
Referenced by MavlinkStreamHighLatency2::write_vehicle_status().
| uint32_t px4_custom_mode::data |
Definition at line 80 of file px4_custom_mode.h.
Referenced by get_mavlink_mode_state(), get_mavlink_navigation_mode(), and MavlinkReceiver::handle_message_set_mode().
| float px4_custom_mode::data_float |
Definition at line 81 of file px4_custom_mode.h.
| uint8_t px4_custom_mode::main_mode |
Definition at line 77 of file px4_custom_mode.h.
Referenced by get_mavlink_navigation_mode(), and MavlinkReceiver::handle_message_set_mode().
| uint16_t px4_custom_mode::reserved |
Definition at line 76 of file px4_custom_mode.h.
| uint16_t px4_custom_mode::reserved_hl |
Definition at line 83 of file px4_custom_mode.h.
| uint8_t px4_custom_mode::sub_mode |
Definition at line 78 of file px4_custom_mode.h.
Referenced by get_mavlink_navigation_mode(), and MavlinkReceiver::handle_message_set_mode().