15 #include <unordered_map> 26 typedef std::unordered_map<uint32_t, const std::string>
cmode_map;
47 { 16,
"INITIALISING" },
79 { 20,
"GUIDED_NOGPS" }
98 { 16,
"INITIALISING" }
158 auto it = cmap.find(custom_mode);
159 if (it != cmap.end())
182 return type == UAS::MAV_TYPE::QUADROTOR ||
183 type == UAS::MAV_TYPE::HEXAROTOR ||
184 type == UAS::MAV_TYPE::OCTOROTOR ||
185 type == UAS::MAV_TYPE::TRICOPTER ||
186 type == UAS::MAV_TYPE::COAXIAL;
191 if (!(base_mode &
enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED)))
196 if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
199 else if (
type == MAV_TYPE::FIXED_WING)
201 else if (
type == MAV_TYPE::GROUND_ROVER)
203 else if (
type == MAV_TYPE::SURFACE_BOAT)
205 else if (
type == MAV_TYPE::SUBMARINE)
212 else if (MAV_AUTOPILOT::PX4 == ap)
226 for (
auto &mode : cmap) {
227 if (mode.second == cmode_str) {
236 cmode = std::stoi(cmode_str, 0, 0);
239 catch (std::invalid_argument &ex) {
244 std::ostringstream os;
245 for (
auto &mode : cmap)
246 os <<
" " << mode.second;
257 std::transform(cmode_str.begin(), cmode_str.end(), cmode_str.begin(), std::ref(toupper));
261 if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
264 else if (type == MAV_TYPE::FIXED_WING)
266 else if (type == MAV_TYPE::GROUND_ROVER)
268 else if (type == MAV_TYPE::SURFACE_BOAT)
270 else if (type == MAV_TYPE::SUBMARINE)
273 else if (MAV_AUTOPILOT::PX4 == ap)
static std::string str_base_mode(int base_mode)
#define ROS_WARN_COND_NAMED(cond, name,...)
bool cmode_from_str(std::string cmode_str, uint32_t &custom_mode)
Lookup custom mode for given string.
mavlink::minimal::MAV_TYPE MAV_TYPE
#define ROS_WARN_THROTTLE_NAMED(rate, name,...)
std::string format(const std::string &fmt, Args...args)
#define ROS_ERROR_STREAM_NAMED(name, args)
static const cmode_map apmrover2_cmode_map
MAV_AUTOPILOT get_autopilot()
Returns autopilot type.
static std::string str_mode_px4(uint32_t custom_mode_int)
static bool is_apm_copter(UAS::MAV_TYPE type)
#define ROS_INFO_STREAM_NAMED(name, args)
static std::string str_custom_mode(uint32_t custom_mode)
static bool cmode_find_cmap(const cmode_map &cmap, std::string &cmode_str, uint32_t &cmode)
static const cmode_map ardusub_cmode_map
constexpr uint32_t define_mode_auto(enum custom_mode::SUB_MODE_AUTO sm)
helper function to define auto mode as uint32_t constant
std::atomic< uint8_t > type
std::string str_mode_v10(uint8_t base_mode, uint32_t custom_mode)
Represent FCU mode as string.
static const cmode_map arduplane_cmode_map
static std::string str_mode_cmap(const cmode_map &cmap, uint32_t custom_mode)
MAV_TYPE get_type()
Returns vehicle type.
static const cmode_map arducopter_cmode_map
PX4 custom mode constantsPX4 custom flight modes.
#define ROS_ERROR_NAMED(name,...)
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
std::unordered_map< uint32_t, const std::string > cmode_map
constexpr std::underlying_type< _T >::type enum_value(_T e)
static const cmode_map px4_cmode_map
PX4 custom mode -> string.