20 #include <Eigen/Geometry> 23 #include <mavconn/mavlink_dialect.h> 55 constexpr
typename std::underlying_type<_T>::type
enum_value(_T e)
57 return static_cast<typename std::underlying_type<_T>::type
>(e);
68 std::string
to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
70 std::string
to_string(mavlink::common::MAV_AUTOPILOT e);
71 std::string
to_string(mavlink::common::MAV_TYPE e);
72 std::string
to_string(mavlink::common::MAV_STATE e);
73 std::string
to_string(mavlink::common::MAV_COMPONENT e);
74 std::string
to_string(mavlink::common::MAV_ESTIMATOR_TYPE e);
75 std::string
to_string(mavlink::common::ADSB_ALTITUDE_TYPE e);
76 std::string
to_string(mavlink::common::ADSB_EMITTER_TYPE e);
77 std::string
to_string(mavlink::common::MAV_MISSION_RESULT e);
78 std::string
to_string(mavlink::common::MAV_FRAME e);
79 std::string
to_string(mavlink::common::MAV_DISTANCE_SENSOR e);
80 std::string
to_string(mavlink::common::LANDING_TARGET_TYPE e);
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
Retreive MAV_FRAME from name.
std::string format(const std::string &fmt, Args...args)
Eigen::Quaterniond sensor_orientation_matching(mavlink::common::MAV_SENSOR_ORIENTATION orientation)
Function to match the received orientation received by MAVLink msg and the rotation of the sensor rel...
mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type)
Retreive MAV_TYPE from name.
std::string to_string_enum(int e)
std::string to_string(timesync_mode e)
timesync_mode timesync_mode_from_str(const std::string &mode)
Retrieve timesync mode from name.
int sensor_orientation_from_str(const std::string &sensor_orientation)
Retrieve sensor orientation number from alias name.
mavlink::common::LANDING_TARGET_TYPE landing_target_type_from_str(const std::string &landing_target_type)
Retrieve landing target type from alias name.
constexpr std::underlying_type< _T >::type enum_value(_T e)