#include <array>
#include <unordered_map>
#include <stdexcept>
#include <mavros/mavros_uas.h>
#include <mavros/px4_custom_mode.h>
Go to the source code of this file.
|
typedef std::unordered_map< uint32_t, const std::string > | cmode_map |
|
typedef std::unordered_map<uint32_t, const std::string> cmode_map |
static bool cmode_find_cmap |
( |
const cmode_map & |
cmap, |
|
|
std::string & |
cmode_str, |
|
|
uint32_t & |
cmode |
|
) |
| |
|
static |
static std::string str_base_mode |
( |
int |
base_mode | ) |
|
|
inlinestatic |
static std::string str_custom_mode |
( |
uint32_t |
custom_mode | ) |
|
|
static |
static std::string str_mode_cmap |
( |
const cmode_map & |
cmap, |
|
|
uint32_t |
custom_mode |
|
) |
| |
|
static |
static std::string str_mode_px4 |
( |
uint32_t |
custom_mode_int | ) |
|
|
inlinestatic |
Initial value:{{
{ 0, "MANUAL" },
{ 1, "ACRO" },
{ 3, "STEERING" },
{ 4, "HOLD" },
{ 5, "LOITER" },
{ 6, "FOLLOW" },
{ 7, "SIMPLE" },
{ 10, "AUTO" },
{ 11, "RTL" },
{ 12, "SMART_RTL" },
{ 15, "GUIDED" },
{ 16, "INITIALISING" }
}}
APM:Rover custom mode -> string
APMrover2/defines.h
Definition at line 86 of file uas_stringify.cpp.
Initial value:{{
{ 0, "STABILIZE" },
{ 1, "ACRO" },
{ 2, "ALT_HOLD" },
{ 3, "AUTO" },
{ 4, "GUIDED" },
{ 5, "LOITER" },
{ 6, "RTL" },
{ 7, "CIRCLE" },
{ 8, "POSITION" },
{ 9, "LAND" },
{ 10, "OF_LOITER" },
{ 11, "DRIFT" },
{ 13, "SPORT" },
{ 14, "FLIP" },
{ 15, "AUTOTUNE" },
{ 16, "POSHOLD" },
{ 17, "BRAKE" },
{ 18, "THROW" },
{ 19, "AVOID_ADSB" },
{ 20, "GUIDED_NOGPS" }
}}
APM:Copter custom mode -> string
ArduCopter/defines.h
Definition at line 59 of file uas_stringify.cpp.
Initial value:{{
{ 0, "MANUAL" },
{ 1, "CIRCLE" },
{ 2, "STABILIZE" },
{ 3, "TRAINING" },
{ 4, "ACRO" },
{ 5, "FBWA" },
{ 6, "FBWB" },
{ 7, "CRUISE" },
{ 8, "AUTOTUNE" },
{ 10, "AUTO" },
{ 11, "RTL" },
{ 12, "LOITER" },
{ 14, "LAND" },
{ 15, "GUIDED" },
{ 16, "INITIALISING" },
{ 17, "QSTABILIZE" },
{ 18, "QHOVER" },
{ 19, "QLOITER" },
{ 20, "QLAND" },
{ 21, "QRTL" }
}}
APM:Plane custom mode -> string
ArduPlane/defines.h
Definition at line 32 of file uas_stringify.cpp.
Initial value:{{
{ 0, "STABILIZE" },
{ 1, "ACRO" },
{ 2, "ALT_HOLD" },
{ 3, "AUTO" },
{ 4, "GUIDED" },
{ 5, "VELHOLD" },
{ 6, "RTL" },
{ 7, "CIRCLE" },
{ 9, "SURFACE" },
{ 10, "OF_LOITER" },
{ 11, "DRIFT" },
{ 13, "TRANSECT" },
{ 14, "FLIP" },
{ 15, "AUTOTUNE" },
{ 16, "POSHOLD" },
{ 17, "BRAKE" },
{ 18, "THROW" },
{ 19, "MANUAL" }
}}
ArduSub custom mode -> string
- Note
- Modes marked n/a is not implemented (defines.h comments)
ArduSub/defines.h
Definition at line 107 of file uas_stringify.cpp.
Initial value:{{
}}
constexpr uint32_t define_mode_auto(enum custom_mode::SUB_MODE_AUTO sm)
helper function to define auto mode as uint32_t constant
constexpr uint32_t define_mode(enum custom_mode::MAIN_MODE mm, uint8_t sm=0)
helper function to define any mode as uint32_t constant
PX4 custom mode -> string.
Definition at line 129 of file uas_stringify.cpp.