18 #include <unordered_map> 24 using mavlink::common::MAV_AUTOPILOT;
25 using mavlink::common::MAV_TYPE;
26 using mavlink::common::MAV_STATE;
27 using mavlink::common::MAV_COMPONENT;
28 using mavlink::common::MAV_ESTIMATOR_TYPE;
29 using mavlink::common::ADSB_ALTITUDE_TYPE;
30 using mavlink::common::ADSB_EMITTER_TYPE;
31 using mavlink::common::GPS_FIX_TYPE;
32 using mavlink::common::MAV_MISSION_RESULT;
33 using mavlink::common::MAV_FRAME;
34 using mavlink::common::MAV_DISTANCE_SENSOR;
35 using mavlink::common::LANDING_TARGET_TYPE;
110 "Reserved for future use",
114 "Generic autopilot only supporting simple waypoints",
115 "Generic autopilot supporting waypoints and other simple navigation commands",
116 "Generic autopilot supporting the full mission command set",
117 "No valid autopilot",
157 "Generic micro air vehicle",
158 "Fixed wing aircraft",
160 "Coaxial helicopter",
161 "Normal helicopter with tail rotor",
162 "Ground installation",
163 "Operator control unit",
175 "Onboard companion controller",
184 "Onboard ADSB peripheral",
189 "Onboard FLARM collision avoidance system",
226 "ONBOARD_CONTROLLER",
277 "Flight_Termination",
324 std::underlying_type<timesync_mode>::type rv = idx;
457 "mission accepted OK",
458 "generic error / not accepting mission commands at all right now",
459 "coordinate frame is not supported",
460 "command is not supported",
461 "mission item exceeds storage space",
462 "one of the parameters has an invalid value",
463 "param1 has an invalid value",
464 "param2 has an invalid value",
465 "param3 has an invalid value",
466 "param4 has an invalid value",
467 "x/param5 has an invalid value",
468 "y/param6 has an invalid value",
469 "param7 has an invalid value",
470 "received waypoint out of sequence",
471 "not accepting any mission commands from this communication partner",
493 "GLOBAL_RELATIVE_ALT",
496 "GLOBAL_RELATIVE_ALT_INT",
500 "GLOBAL_TERRAIN_ALT",
501 "GLOBAL_TERRAIN_ALT_INT",
565 { 158,
"PERIPHERAL" },
566 { 159,
"QX1_GIMBAL" },
569 { 190,
"MISSIONPLANNER" },
570 { 195,
"PATHPLANNER" },
576 { 240,
"UDP_BRIDGE" },
577 { 241,
"UART_BRIDGE" },
578 { 250,
"SYSTEM_CONTROL" },
598 std::underlying_type<MAV_FRAME>::type rv = idx;
604 return MAV_FRAME::LOCAL_NED;
611 std::underlying_type<MAV_TYPE>::type rv = idx;
616 return MAV_TYPE::GENERIC;
668 std::underlying_type<LANDING_TARGET_TYPE>::type rv = idx;
669 return static_cast<LANDING_TARGET_TYPE
>(rv);
672 ROS_ERROR_STREAM_NAMED(
"uas",
"TYPE: Unknown LANDING_TARGET_TYPE: " << landing_target_type <<
". Defaulting to LIGHT_BEACON");
673 return LANDING_TARGET_TYPE::LIGHT_BEACON;
std::string to_name(MAV_TYPE e)
static const std::array< const std::string, 20 > mav_autopilot_strings
MAV_AUTOPILOT values.
static const std::array< const std::string, 4 > timesync_mode_strings
timesync_mode values
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
Retreive MAV_FRAME from name.
#define ROS_ERROR_STREAM_NAMED(name, args)
static const std::array< const std::string, 15 > mav_mission_result_strings
MAV_MISSION_RESULT values.
static const std::array< const std::string, 5 > mav_estimator_type_strings
MAV_ESTIMATOR_TYPE values.
std::string to_string(LANDING_TARGET_TYPE e)
static const std::array< const std::string, 5 > mav_distance_sensor_strings
MAV_DISTANCE_SENSOR values.
static const std::array< const std::string, 33 > mav_type_names
MAV_TYPE values.
static const std::array< const std::string, 20 > mav_frame_strings
MAV_FRAME values.
static const std::array< const std::string, 20 > adsb_emitter_type_strings
ADSB_EMITTER_TYPE values.
static const std::array< const std::string, 33 > mav_type_strings
MAV_TYPE values.
static const std::array< const std::string, 2 > adsb_altitude_type_strings
ADSB_ALTITUDE_TYPE values.
mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type)
Retreive MAV_TYPE from name.
std::string to_string(timesync_mode e)
static const std::array< const std::string, 9 > gps_fix_type_strings
GPS_FIX_TYPE values.
static const std::unordered_map< size_t, const std::string > mav_comp_id_strings
timesync_mode timesync_mode_from_str(const std::string &mode)
Retrieve timesync mode from name.
static const std::array< const std::string, 4 > landing_target_type_strings
LANDING_TARGET_TYPE values.
mavlink::common::LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
Retrieve landing target type from alias name.
static const std::array< const std::string, 9 > mav_state_strings
MAV_STATE values.
constexpr std::underlying_type< _T >::type enum_value(_T e)