#include <array>#include <unordered_map>#include <stdexcept>#include <mavros/mavros_uas.h>#include <mavros/utils.h>#include <mavros/px4_custom_mode.h>
Go to the source code of this file.
Typedefs | |
| typedef std::unordered_map < uint32_t, const std::string > | cmode_map |
Functions | |
| static bool | cmode_find_cmap (const cmode_map &cmap, std::string &cmode_str, uint32_t &cmode) |
| static bool | is_apm_copter (enum MAV_TYPE &type) |
| static std::string | str_base_mode (int base_mode) |
| static std::string | str_custom_mode (uint32_t custom_mode) |
| static std::string | str_mode_cmap (const cmode_map &cmap, uint32_t custom_mode) |
| static std::string | str_mode_px4 (uint32_t custom_mode_int) |
Variables | |
| static const cmode_map | apmrover2_cmode_map |
| static const cmode_map | arducopter_cmode_map |
| static const cmode_map | arduplane_cmode_map |
| static const std::array< const std::string, 18 > | autopilot_strings |
| MAV_AUTOPILOT values. | |
| static const cmode_map | px4_cmode_map |
| PX4 custom mode -> string. | |
| static const std::array< const std::string, 8 > | state_strings |
| static const std::array< const std::string, 28 > | type_strings |
http://mavlink.org/messages/common#ENUM_MAV_TYPE | |
| typedef std::unordered_map<uint32_t, const std::string> cmode_map |
Definition at line 26 of file uas_stringify.cpp.
| static bool cmode_find_cmap | ( | const cmode_map & | cmap, |
| std::string & | cmode_str, | ||
| uint32_t & | cmode | ||
| ) | [static] |
Definition at line 184 of file uas_stringify.cpp.
| static bool is_apm_copter | ( | enum MAV_TYPE & | type | ) | [inline, static] |
Definition at line 145 of file uas_stringify.cpp.
| static std::string str_base_mode | ( | int | base_mode | ) | [inline, static] |
Definition at line 111 of file uas_stringify.cpp.
| static std::string str_custom_mode | ( | uint32_t | custom_mode | ) | [static] |
Definition at line 117 of file uas_stringify.cpp.
| static std::string str_mode_cmap | ( | const cmode_map & | cmap, |
| uint32_t | custom_mode | ||
| ) | [static] |
Definition at line 123 of file uas_stringify.cpp.
| static std::string str_mode_px4 | ( | uint32_t | custom_mode_int | ) | [inline, static] |
Definition at line 131 of file uas_stringify.cpp.
const cmode_map apmrover2_cmode_map [static] |
{
{ 0, "MANUAL" },
{ 2, "LEARNING" },
{ 3, "STEERING" },
{ 4, "HOLD" },
{ 10, "AUTO" },
{ 11, "RTL" },
{ 15, "GUIDED" },
{ 16, "INITIALISING" }
}
APM:Rover custom mode -> string
APMrover2/defines.h
Definition at line 82 of file uas_stringify.cpp.
const cmode_map arducopter_cmode_map [static] |
{
{ 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" }
}
APM:Copter custom mode -> string
ArduCopter/defines.h
Definition at line 58 of file uas_stringify.cpp.
const cmode_map arduplane_cmode_map [static] |
{
{ 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" }
}
APM:Plane custom mode -> string
ArduPlane/defines.h
Definition at line 32 of file uas_stringify.cpp.
const std::array<const std::string, 18> autopilot_strings [static] |
{
"Generic",
"PIXHAWK",
"SLUGS",
"ArduPilotMega",
"OpenPilot",
"Generic-WP-Only",
"Generic-WP-Simple-Nav",
"Generic-Mission-Full",
"INVALID",
"Paparazzi",
"UDB",
"FlexiPilot",
"PX4",
"SMACCMPILOT",
"AUTOQUAD",
"ARMAZILA",
"AEROB",
"ASLUAV"
}
MAV_AUTOPILOT values.
Definition at line 240 of file uas_stringify.cpp.
const cmode_map px4_cmode_map [static] |
{
{ px4::define_mode(px4::custom_mode::MAIN_MODE_MANUAL), "MANUAL" },
{ px4::define_mode(px4::custom_mode::MAIN_MODE_ACRO), "ACRO" },
{ px4::define_mode(px4::custom_mode::MAIN_MODE_ALTCTL), "ALTCTL" },
{ px4::define_mode(px4::custom_mode::MAIN_MODE_POSCTL), "POSCTL" },
{ px4::define_mode(px4::custom_mode::MAIN_MODE_OFFBOARD), "OFFBOARD" },
{ px4::define_mode(px4::custom_mode::MAIN_MODE_STABILIZED), "STABILIZED" },
{ px4::define_mode(px4::custom_mode::MAIN_MODE_RATTITUDE), "RATTITUDE" },
{ px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_MISSION), "AUTO.MISSION" },
{ px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_LOITER), "AUTO.LOITER" },
{ px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_RTL), "AUTO.RTL" },
{ px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_LAND), "AUTO.LAND" },
{ px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_RTGS), "AUTO.RTGS" },
{ px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_READY), "AUTO.READY" },
{ px4::define_mode_auto(px4::custom_mode::SUB_MODE_AUTO_TAKEOFF), "AUTO.TAKEOFF" }
}
PX4 custom mode -> string.
Definition at line 94 of file uas_stringify.cpp.
const std::array<const std::string, 8> state_strings [static] |
{
"Uninit",
"Boot",
"Calibrating",
"Standby",
"Active",
"Critical",
"Emergency",
"Poweroff"
}
Definition at line 311 of file uas_stringify.cpp.
const std::array<const std::string, 28> type_strings [static] |
{
"Generic",
"Fixed-Wing",
"Quadrotor",
"Coaxial-Heli",
"Helicopter",
"Antenna-Tracker",
"GCS",
"Airship",
"Free-Balloon",
"Rocket",
"Ground-Rover",
"Surface-Boat",
"Submarine",
"Hexarotor",
"Octorotor",
"Tricopter",
"Flapping-Wing",
"Kite",
"Onboard-Controller",
"VTOL-Duorotor",
"VTOL-Quadrotor",
"VTOL-Tiltrotor",
"VTOL-RESERVED2",
"VTOL-RESERVED3",
"VTOL-RESERVED4",
"VTOL-RESERVED5",
"Gimbal",
"ADS-B"
}
http://mavlink.org/messages/common#ENUM_MAV_TYPE
Definition at line 271 of file uas_stringify.cpp.