PX4 custom mode. More...
#include <px4_custom_mode.h>
Public Types | |
enum | MAIN_MODE : uint8_t { MAIN_MODE_MANUAL = 1, MAIN_MODE_ALTCTL, MAIN_MODE_POSCTL, MAIN_MODE_AUTO, MAIN_MODE_ACRO, MAIN_MODE_OFFBOARD, MAIN_MODE_STABILIZED, MAIN_MODE_RATTITUDE } |
enum | SUB_MODE_AUTO : uint8_t { SUB_MODE_AUTO_READY = 1, SUB_MODE_AUTO_TAKEOFF, SUB_MODE_AUTO_LOITER, SUB_MODE_AUTO_MISSION, SUB_MODE_AUTO_RTL, SUB_MODE_AUTO_LAND, SUB_MODE_AUTO_RTGS, SUB_MODE_AUTO_FOLLOW_TARGET, SUB_MODE_AUTO_PRECLAND } |
Public Member Functions | |
custom_mode () | |
custom_mode (uint32_t val) | |
constexpr | custom_mode (uint8_t mm, uint8_t sm) |
Public Attributes | |
struct { | |
uint8_t main_mode | |
uint16_t reserved | |
uint8_t sub_mode | |
}; | |
uint32_t | data |
float | data_float |
PX4 custom mode.
This union decodes uint32_t HEARTBEAT.custom_mode and uint32_t SET_MODE.custom_mode.
Definition at line 55 of file px4_custom_mode.h.
enum px4::custom_mode::MAIN_MODE : uint8_t |
Enumerator | |
---|---|
MAIN_MODE_MANUAL | |
MAIN_MODE_ALTCTL | |
MAIN_MODE_POSCTL | |
MAIN_MODE_AUTO | |
MAIN_MODE_ACRO | |
MAIN_MODE_OFFBOARD | |
MAIN_MODE_STABILIZED | |
MAIN_MODE_RATTITUDE |
Definition at line 56 of file px4_custom_mode.h.
enum px4::custom_mode::SUB_MODE_AUTO : uint8_t |
Definition at line 67 of file px4_custom_mode.h.
|
inline |
Definition at line 87 of file px4_custom_mode.h.
|
inlineexplicit |
Definition at line 90 of file px4_custom_mode.h.
|
inline |
Definition at line 93 of file px4_custom_mode.h.
struct { ... } |
uint32_t px4::custom_mode::data |
Definition at line 84 of file px4_custom_mode.h.
float px4::custom_mode::data_float |
Definition at line 85 of file px4_custom_mode.h.
uint8_t px4::custom_mode::main_mode |
Definition at line 81 of file px4_custom_mode.h.
uint16_t px4::custom_mode::reserved |
Definition at line 80 of file px4_custom_mode.h.
uint8_t px4::custom_mode::sub_mode |
Definition at line 82 of file px4_custom_mode.h.