Union custom_mode

Union Documentation

union custom_mode
#include <px4_custom_mode.hpp>

PX4 custom mode.

This union decodes uint32_t HEARTBEAT.custom_mode and uint32_t SET_MODE.custom_mode.

Public Types

enum MAIN_MODE

Values:

enumerator MAIN_MODE_MANUAL
enumerator MAIN_MODE_ALTCTL
enumerator MAIN_MODE_POSCTL
enumerator MAIN_MODE_AUTO
enumerator MAIN_MODE_ACRO
enumerator MAIN_MODE_OFFBOARD
enumerator MAIN_MODE_STABILIZED
enumerator MAIN_MODE_RATTITUDE
enum SUB_MODE_AUTO

Values:

enumerator SUB_MODE_AUTO_READY
enumerator SUB_MODE_AUTO_TAKEOFF
enumerator SUB_MODE_AUTO_LOITER
enumerator SUB_MODE_AUTO_MISSION
enumerator SUB_MODE_AUTO_RTL
enumerator SUB_MODE_AUTO_LAND
enumerator SUB_MODE_AUTO_RTGS
enumerator SUB_MODE_AUTO_FOLLOW_TARGET
enumerator SUB_MODE_AUTO_PRECLAND

Public Functions

inline custom_mode()
inline explicit custom_mode(uint32_t val)
inline constexpr custom_mode(uint8_t mm, uint8_t sm)

Public Members

struct px4::custom_mode::mode_type mode
uint32_t data
float data_float
struct mode_type

Public Members

uint16_t reserved
uint8_t main_mode
uint8_t sub_mode