.. _program_listing_file__tmp_ws_src_mavros_mavros_include_mavros_utils.hpp: Program Listing for File utils.hpp ================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/mavros/mavros/include/mavros/utils.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* * Copyright 2014,2015,2016,2021 Vladimir Ermakov. * * This file is part of the mavros package and subject to the license terms * in the top-level LICENSE file of the mavros repository. * https://github.com/mavlink/mavros/tree/master/LICENSE.md */ #pragma once #ifndef MAVROS__UTILS_HPP_ #define MAVROS__UTILS_HPP_ #include #include // NOLINT #include "mavconn/thread_utils.hpp" #include "mavros_msgs/mavlink_convert.hpp" #include "mavconn/mavlink_dialect.hpp" // OS X compat: missing error codes #ifdef __APPLE__ #define EBADE 50 /* Invalid exchange */ #define EBADFD 81 /* File descriptor in bad state */ #define EBADRQC 54 /* Invalid request code */ #define EBADSLT 55 /* Invalid slot */ #endif namespace mavros { namespace utils { using mavconn::utils::format; using mavconn::utils::set_this_thread_name; enum class timesync_mode { NONE = 0, MAVLINK, ONBOARD, PASSTHROUGH, }; template constexpr typename std::underlying_type<_T>::type enum_value(_T e) { return static_cast::type>(e); } std::string to_string(timesync_mode e); std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e); std::string to_string(mavlink::minimal::MAV_AUTOPILOT e); std::string to_string(mavlink::minimal::MAV_TYPE e); std::string to_string(mavlink::minimal::MAV_STATE e); std::string to_string(mavlink::minimal::MAV_COMPONENT e); std::string to_string(mavlink::common::MAV_ESTIMATOR_TYPE e); std::string to_string(mavlink::common::ADSB_ALTITUDE_TYPE e); std::string to_string(mavlink::common::ADSB_EMITTER_TYPE e); std::string to_string(mavlink::common::MAV_MISSION_RESULT e); std::string to_string(mavlink::common::MAV_FRAME e); std::string to_string(mavlink::common::MAV_DISTANCE_SENSOR e); std::string to_string(mavlink::common::LANDING_TARGET_TYPE e); template std::string to_string_enum(int e) { return to_string(static_cast<_T>(e)); } std::string enum_to_name(mavlink::minimal::MAV_TYPE e); Eigen::Quaterniond sensor_orientation_matching(mavlink::common::MAV_SENSOR_ORIENTATION orientation); int sensor_orientation_from_str(const std::string & sensor_orientation); timesync_mode timesync_mode_from_str(const std::string & mode); mavlink::common::MAV_FRAME mav_frame_from_str(const std::string & mav_frame); mavlink::minimal::MAV_TYPE mav_type_from_str(const std::string & mav_type); mavlink::common::LANDING_TARGET_TYPE landing_target_type_from_str( const std::string & landing_target_type); } // namespace utils } // namespace mavros #endif // MAVROS__UTILS_HPP_