Namespaces | Classes | Macros | Typedefs | Enumerations | Functions | Variables
Nodelib

MAVROS node implementation. More...

Collaboration diagram for Nodelib:

Namespaces

 mavros
 
 mavros::ftf
 
 mavros::ftf::detail
 
 mavros::utils
 

Classes

class  mavros::MavlinkDiag
 
class  mavros::MavRos
 MAVROS node class. More...
 
class  mavros::UAS
 UAS for plugins. More...
 

Macros

#define UAS_DIAG(uasobjptr)   ((uasobjptr)->diag_updater)
 helper accessor to diagnostic updater More...
 
#define UAS_FCU(uasobjptr)   ((uasobjptr)->fcu_link)
 helper accessor to FCU link interface More...
 

Typedefs

using mavros::UAS::CapabilitiesCb = std::function< void(MAV_CAP)>
 
using mavros::UAS::ConnectionCb = std::function< void(bool)>
 
using mavros::ftf::Covariance3d = sensor_msgs::Imu::_angular_velocity_covariance_type
 Type matching rosmsg for 3x3 covariance matrix. More...
 
using mavros::ftf::Covariance6d = geometry_msgs::PoseWithCovariance::_covariance_type
 Type matching rosmsg for 6x6 covariance matrix. More...
 
using mavros::ftf::Covariance9d = boost::array< double, 81 >
 Type matching rosmsg for 9x9 covariance matrix. More...
 
using mavros::ftf::EigenMapConstCovariance3d = Eigen::Map< const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > >
 
using mavros::ftf::EigenMapConstCovariance6d = Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > >
 
using mavros::ftf::EigenMapConstCovariance9d = Eigen::Map< const Eigen::Matrix< double, 9, 9, Eigen::RowMajor > >
 
using mavros::ftf::EigenMapCovariance3d = Eigen::Map< Eigen::Matrix< double, 3, 3, Eigen::RowMajor > >
 Eigen::Map for Covariance3d. More...
 
using mavros::ftf::EigenMapCovariance6d = Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > >
 Eigen::Map for Covariance6d. More...
 
using mavros::ftf::EigenMapCovariance9d = Eigen::Map< Eigen::Matrix< double, 9, 9, Eigen::RowMajor > >
 Eigen::Map for Covariance9d. More...
 
using mavros::UAS::lock_guard = std::lock_guard< std::recursive_mutex >
 
using mavros::ftf::detail::Matrix6d = Eigen::Matrix< double, 6, 6 >
 Auxiliar matrices to Covariance transforms. More...
 
using mavros::ftf::detail::Matrix9d = Eigen::Matrix< double, 9, 9 >
 
using mavros::UAS::MAV_AUTOPILOT = mavlink::minimal::MAV_AUTOPILOT
 
using mavros::UAS::MAV_CAP = mavlink::common::MAV_PROTOCOL_CAPABILITY
 
using mavros::UAS::MAV_MODE_FLAG = mavlink::minimal::MAV_MODE_FLAG
 
using mavros::UAS::MAV_STATE = mavlink::minimal::MAV_STATE
 
using mavros::UAS::MAV_TYPE = mavlink::minimal::MAV_TYPE
 
using mavros::utils::OrientationPair = std::pair< const std::string, const Eigen::Quaterniond >
 
using mavros::UAS::timesync_mode = utils::timesync_mode
 
using mavros::UAS::unique_lock = std::unique_lock< std::recursive_mutex >
 

Enumerations

enum  mavros::ftf::StaticEcefTF { mavros::ftf::StaticEcefTF::ECEF_TO_ENU, mavros::ftf::StaticEcefTF::ENU_TO_ECEF }
 Orientation transform options when applying rotations to data, for ECEF. More...
 
enum  mavros::ftf::StaticTF {
  mavros::ftf::StaticTF::NED_TO_ENU, mavros::ftf::StaticTF::ENU_TO_NED, mavros::ftf::StaticTF::AIRCRAFT_TO_BASELINK, mavros::ftf::StaticTF::BASELINK_TO_AIRCRAFT,
  mavros::ftf::StaticTF::ABSOLUTE_FRAME_AIRCRAFT_TO_BASELINK, mavros::ftf::StaticTF::ABSOLUTE_FRAME_BASELINK_TO_AIRCRAFT
}
 Orientation transform options when applying rotations to data. More...
 

Functions

void mavros::UAS::add_capabilities_change_handler (CapabilitiesCb cb)
 Adds a function to the capabilities callback queue. More...
 
void mavros::UAS::add_connection_change_handler (ConnectionCb cb)
 Add connection change handler callback. More...
 
void mavros::MavRos::add_plugin (std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist)
 load plugin More...
 
void mavros::UAS::add_static_transform (const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr, std::vector< geometry_msgs::TransformStamped > &vector)
 Add static transform. To publish all static transforms at once, we stack them in a std::vector. More...
 
static const Eigen::Affine3d mavros::ftf::detail::AIRCRAFT_BASELINK_AFFINE (AIRCRAFT_BASELINK_Q)
 Static vector needed for rotating between aircraft and base_link frames +PI rotation around X (Forward) axis transforms from Forward, Right, Down (aircraft) Fto Forward, Left, Up (base_link) frames. More...
 
bool mavros::UAS::cmode_from_str (std::string cmode_str, uint32_t &custom_mode)
 Lookup custom mode for given string. More...
 
template<class T , std::size_t SIZE>
void mavros::ftf::covariance_to_mavlink (const T &cov, std::array< float, SIZE > &covmsg)
 Convert covariance matrix to MAVLink float[n] format. More...
 
template<class T , std::size_t ARR_SIZE>
void mavros::ftf::covariance_urt_to_mavlink (const T &covmap, std::array< float, ARR_SIZE > &covmsg)
 Convert upper right triangular of a covariance matrix to MAVLink float[n] format. More...
 
template<class T >
double mavros::UAS::ellipsoid_to_geoid_height (T lla)
 Conversion from height above ellipsoid (WGS-84) to height above geoid (AMSL) More...
 
template<class T >
double mavros::UAS::geoid_to_ellipsoid_height (T lla)
 Conversion from height above geoid (AMSL) to height above ellipsoid (WGS-84) More...
 
bool mavros::UAS::get_armed ()
 Returns arming status. More...
 
geometry_msgs::Vector3 mavros::UAS::get_attitude_angular_velocity_enu ()
 Get angular velocity from IMU data. More...
 
geometry_msgs::Vector3 mavros::UAS::get_attitude_angular_velocity_ned ()
 Get angular velocity from IMU data. More...
 
sensor_msgs::Imu::Ptr mavros::UAS::get_attitude_imu_enu ()
 Get IMU data [ENU]. More...
 
sensor_msgs::Imu::Ptr mavros::UAS::get_attitude_imu_ned ()
 Get IMU data [NED]. More...
 
geometry_msgs::Quaternion mavros::UAS::get_attitude_orientation_enu ()
 Get Attitude orientation quaternion. More...
 
geometry_msgs::Quaternion mavros::UAS::get_attitude_orientation_ned ()
 Get Attitude orientation quaternion. More...
 
MAV_AUTOPILOT mavros::UAS::get_autopilot ()
 Returns autopilot type. More...
 
uint64_t mavros::UAS::get_capabilities ()
 
void mavros::UAS::get_gps_epts (float &eph, float &epv, int &fix_type, int &satellites_visible)
 Returns EPH, EPV, Fix type and satellites visible. More...
 
sensor_msgs::NavSatFix::Ptr mavros::UAS::get_gps_fix ()
 Retunrs last GPS RAW message. More...
 
bool mavros::UAS::get_hil_state ()
 Returns HIL status. More...
 
uint8_t mavros::UAS::get_tgt_component ()
 Return communication target component. More...
 
uint8_t mavros::UAS::get_tgt_system ()
 Return communication target system. More...
 
uint64_t mavros::UAS::get_time_offset (void)
 
timesync_mode mavros::UAS::get_timesync_mode (void)
 
MAV_TYPE mavros::UAS::get_type ()
 Returns vehicle type. More...
 
template<typename ... Ts>
bool mavros::UAS::has_capabilities (Ts ... capabilities)
 Function to check if the flight controller has a set of capabilities. More...
 
template<typename T >
bool mavros::UAS::has_capability (T capability)
 Function to check if the flight controller has a capability. More...
 
bool mavros::UAS::is_ardupilotmega ()
 Check that FCU is APM. More...
 
bool mavros::UAS::is_connected ()
 Return connection status. More...
 
bool mavros::UAS::is_my_target (uint8_t sysid, uint8_t compid)
 Check that sys/comp id's is my target. More...
 
bool mavros::UAS::is_my_target (uint8_t sysid)
 Check that system id is my target. More...
 
bool mavros::UAS::is_px4 ()
 Check that FCU is PX4. More...
 
void mavros::MavRos::log_connect_change (bool connected)
 
static const OrientationPair mavros::utils::make_orientation (const std::string &name, const double roll, const double pitch, const double yaw)
 
void mavros::MavRos::mavlink_pub_cb (const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
 fcu link -> ros More...
 
void mavros::MavRos::mavlink_sub_cb (const mavros_msgs::Mavlink::ConstPtr &rmsg)
 ros -> fcu link More...
 
Eigen::Quaterniond mavros::ftf::mavlink_to_quaternion (const std::array< float, 4 > &q)
 Convert Mavlink float[4] quaternion to Eigen. More...
 
template<class T , std::size_t ARR_SIZE>
void mavros::ftf::mavlink_urt_to_covariance_matrix (const std::array< float, ARR_SIZE > &covmsg, T &covmat)
 Convert MAVLink float[n] format (upper right triangular of a covariance matrix) to Eigen::MatrixXd<n,n> full covariance matrix. More...
 
 mavros::MavlinkDiag::MavlinkDiag (std::string name)
 
 mavros::MavRos::MavRos ()
 
template<typename _T >
void mavros::UAS::msg_set_target (_T &msg)
 
static const Eigen::Affine3d mavros::ftf::detail::NED_ENU_AFFINE (NED_ENU_Q)
 Static vector needed for rotating between ENU and NED frames +PI rotation around X (North) axis follwed by +PI/2 rotation about Z (Down) gives the ENU frame. Similarly, a +PI rotation about X (East) followed by a +PI/2 roation about Z (Up) gives the NED frame. More...
 
static const Eigen::PermutationMatrix< 3 > mavros::ftf::detail::NED_ENU_REFLECTION_XY (Eigen::Vector3i(1, 0, 2))
 Use reflections instead of rotations for NED <-> ENU transformation to avoid NaN/Inf floating point pollution across different axes since in NED <-> ENU the axes are perfectly aligned. More...
 
static const Eigen::DiagonalMatrix< double, 3 > mavros::ftf::detail::NED_ENU_REFLECTION_Z (1, 1,-1)
 
void mavros::MavRos::plugin_route_cb (const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing)
 message router More...
 
void mavros::UAS::publish_static_transform (const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr)
 Publishes static transform. More...
 
Eigen::Quaterniond mavros::ftf::quaternion_from_rpy (const Eigen::Vector3d &rpy)
 Convert euler angles to quaternion. More...
 
Eigen::Quaterniond mavros::ftf::quaternion_from_rpy (const double roll, const double pitch, const double yaw)
 Convert euler angles to quaternion. More...
 
double mavros::ftf::quaternion_get_yaw (const Eigen::Quaterniond &q)
 Get Yaw angle from quaternion. More...
 
template<typename _Scalar , typename std::enable_if< std::is_floating_point< _Scalar >::value, bool >::type = true>
void mavros::ftf::quaternion_to_mavlink (const Eigen::Quaternion< _Scalar > &q, std::array< float, 4 > &qmsg)
 Store Quaternion to MAVLink float[4] format. More...
 
Eigen::Vector3d mavros::ftf::quaternion_to_rpy (const Eigen::Quaterniond &q)
 Convert quaternion to euler angles. More...
 
void mavros::ftf::quaternion_to_rpy (const Eigen::Quaterniond &q, double &roll, double &pitch, double &yaw)
 Convert quaternion to euler angles. More...
 
void mavros::MavlinkDiag::run (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
Eigen::Quaterniond mavros::utils::sensor_orientation_matching (MAV_SENSOR_ORIENTATION orientation)
 
void mavros::MavlinkDiag::set_connection_status (bool connected)
 
void mavros::MavlinkDiag::set_mavconn (const mavconn::MAVConnInterface::Ptr &link)
 
void mavros::UAS::set_tgt (uint8_t sys, uint8_t comp)
 
void mavros::UAS::set_time_offset (uint64_t offset_ns)
 
void mavros::UAS::set_timesync_mode (timesync_mode mode)
 
void mavros::MavRos::spin ()
 
void mavros::MavRos::startup_px4_usb_quirk ()
 start mavlink app on USB More...
 
std::string mavros::UAS::str_mode_v10 (uint8_t base_mode, uint32_t custom_mode)
 Represent FCU mode as string. More...
 
ros::Time mavros::UAS::synchronise_stamp (uint32_t time_boot_ms)
 Compute FCU message time from time_boot_ms or time_usec field. More...
 
ros::Time mavros::UAS::synchronise_stamp (uint64_t time_usec)
 
template<typename T >
std_msgs::Header mavros::UAS::synchronized_header (const std::string &frame_id, const T time_stamp)
 Create message header from time_boot_ms or time_usec stamps and frame_id. More...
 
Eigen::Vector3d mavros::ftf::to_eigen (const geometry_msgs::Point r)
 Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d. More...
 
Eigen::Vector3d mavros::ftf::to_eigen (const geometry_msgs::Vector3 r)
 Helper to convert common ROS geometry_msgs::Vector3 to Eigen::Vector3d. More...
 
Eigen::Quaterniond mavros::ftf::to_eigen (const geometry_msgs::Quaternion r)
 Helper to convert common ROS geometry_msgs::Quaternion to Eigen::Quaterniond. More...
 
std::string mavros::utils::to_name (MAV_TYPE e)
 
std::string mavros::utils::to_string (MAV_SENSOR_ORIENTATION orientation)
 
std::string mavros::utils::to_string (MAV_AUTOPILOT e)
 
std::string mavros::utils::to_string (MAV_TYPE e)
 
std::string mavros::utils::to_string (MAV_STATE e)
 
std::string mavros::utils::to_string (ADSB_ALTITUDE_TYPE e)
 
std::string mavros::utils::to_string (ADSB_EMITTER_TYPE e)
 
std::string mavros::utils::to_string (MAV_ESTIMATOR_TYPE e)
 
std::string mavros::utils::to_string (GPS_FIX_TYPE e)
 
std::string mavros::utils::to_string (MAV_MISSION_RESULT e)
 
std::string mavros::utils::to_string (MAV_FRAME e)
 
std::string mavros::utils::to_string (MAV_COMPONENT e)
 
std::string mavros::utils::to_string (MAV_DISTANCE_SENSOR e)
 
std::string mavros::utils::to_string (LANDING_TARGET_TYPE e)
 
Eigen::Vector3d mavros::ftf::detail::transform_frame (const Eigen::Vector3d &vec, const Eigen::Quaterniond &q)
 Transform data expressed in one frame to another frame. More...
 
Covariance3d mavros::ftf::detail::transform_frame (const Covariance3d &cov, const Eigen::Quaterniond &q)
 Transform 3x3 convariance expressed in one frame to another. More...
 
Covariance6d mavros::ftf::detail::transform_frame (const Covariance6d &cov, const Eigen::Quaterniond &q)
 Transform 6x6 convariance expressed in one frame to another. More...
 
Covariance9d mavros::ftf::detail::transform_frame (const Covariance9d &cov, const Eigen::Quaterniond &q)
 Transform 9x9 convariance expressed in one frame to another. More...
 
template<class T >
mavros::ftf::transform_frame_aircraft_baselink (const T &in)
 Transform data expressed in Aircraft frame to Baselink frame. More...
 
template<class T >
mavros::ftf::transform_frame_aircraft_enu (const T &in, const Eigen::Quaterniond &q)
 Transform data expressed in aircraft frame to ENU frame. Assumes quaternion represents rotation from aircraft frame to ENU frame. More...
 
template<class T >
mavros::ftf::transform_frame_aircraft_ned (const T &in, const Eigen::Quaterniond &q)
 Transform data expressed in aircraft frame to NED frame. Assumes quaternion represents rotation from aircraft frame to NED frame. More...
 
template<class T >
mavros::ftf::transform_frame_baselink_aircraft (const T &in)
 Transform data expressed in Baselink frame to Aircraft frame. More...
 
template<class T >
mavros::ftf::transform_frame_baselink_enu (const T &in, const Eigen::Quaterniond &q)
 Transform data expressed in baselink to ENU frame. Assumes quaternion represents rotation from basel_link to ENU frame. More...
 
template<class T >
mavros::ftf::transform_frame_ecef_enu (const T &in, const T &map_origin)
 Transform data expressed in ECEF frame to ENU frame. More...
 
template<class T >
mavros::ftf::transform_frame_enu_aircraft (const T &in, const Eigen::Quaterniond &q)
 Transform data expressed in ENU to aircraft frame. Assumes quaternion represents rotation from ENU to aircraft frame. More...
 
template<class T >
mavros::ftf::transform_frame_enu_baselink (const T &in, const Eigen::Quaterniond &q)
 Transform data expressed in ENU to base_link frame. Assumes quaternion represents rotation from ENU to base_link frame. More...
 
template<class T >
mavros::ftf::transform_frame_enu_ecef (const T &in, const T &map_origin)
 Transform data expressed in ENU frame to ECEF frame. More...
 
template<class T >
mavros::ftf::transform_frame_enu_ned (const T &in)
 Transform data expressed in ENU to NED frame. More...
 
template<class T >
mavros::ftf::transform_frame_ned_aircraft (const T &in, const Eigen::Quaterniond &q)
 Transform data expressed in NED to aircraft frame. Assumes quaternion represents rotation from NED to aircraft frame. More...
 
template<class T >
mavros::ftf::transform_frame_ned_enu (const T &in)
 Transform data expressed in NED to ENU frame. More...
 
Eigen::Quaterniond mavros::ftf::detail::transform_orientation (const Eigen::Quaterniond &q, const StaticTF transform)
 Transform representation of attitude from 1 frame to another (e.g. transfrom attitude from representing from base_link -> NED to representing base_link -> ENU) More...
 
template<class T >
mavros::ftf::transform_orientation_absolute_frame_aircraft_baselink (const T &in)
 Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame, treating aircraft frame as in an absolute frame of reference (local NED). More...
 
template<class T >
mavros::ftf::transform_orientation_absolute_frame_baselink_aircraft (const T &in)
 Transform from attitude represented WRT baselink frame to attitude represented WRT body frame, treating baselink frame as in an absolute frame of reference (local NED). More...
 
template<class T >
mavros::ftf::transform_orientation_aircraft_baselink (const T &in)
 Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame. More...
 
template<class T >
mavros::ftf::transform_orientation_baselink_aircraft (const T &in)
 Transform from attitude represented WRT baselink frame to attitude represented WRT body frame. More...
 
template<class T >
mavros::ftf::transform_orientation_enu_ned (const T &in)
 Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame. More...
 
template<class T >
mavros::ftf::transform_orientation_ned_enu (const T &in)
 Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame. More...
 
Eigen::Vector3d mavros::ftf::detail::transform_static_frame (const Eigen::Vector3d &vec, const StaticTF transform)
 Transform data expressed in one frame to another frame. More...
 
Covariance3d mavros::ftf::detail::transform_static_frame (const Covariance3d &cov, const StaticTF transform)
 Transform 3d convariance expressed in one frame to another. More...
 
Covariance6d mavros::ftf::detail::transform_static_frame (const Covariance6d &cov, const StaticTF transform)
 Transform 6d convariance expressed in one frame to another. More...
 
Covariance9d mavros::ftf::detail::transform_static_frame (const Covariance9d &cov, const StaticTF transform)
 Transform 9d convariance expressed in one frame to another. More...
 
Eigen::Vector3d mavros::ftf::detail::transform_static_frame (const Eigen::Vector3d &vec, const Eigen::Vector3d &map_origin, const StaticEcefTF transform)
 Transform data expressed in one frame to another frame with additional map origin parameter. More...
 
 mavros::UAS::UAS ()
 
void mavros::UAS::update_attitude_imu_enu (sensor_msgs::Imu::Ptr &imu)
 Store IMU data [ENU]. More...
 
void mavros::UAS::update_attitude_imu_ned (sensor_msgs::Imu::Ptr &imu)
 Store IMU data [NED]. More...
 
void mavros::UAS::update_capabilities (bool known, uint64_t caps=0)
 Update the capabilities if they've changed every VERSION/timeout. More...
 
void mavros::UAS::update_connection_status (bool conn_)
 
void mavros::UAS::update_gps_fix_epts (sensor_msgs::NavSatFix::Ptr &fix, float eph, float epv, int fix_type, int satellites_visible)
 Store GPS RAW data. More...
 
void mavros::UAS::update_heartbeat (uint8_t type_, uint8_t autopilot_, uint8_t base_mode_)
 
 mavros::MavRos::~MavRos ()
 
 mavros::UAS::~UAS ()
 

Variables

static const std::array< const std::string, 2 > mavros::utils::adsb_altitude_type_strings
 ADSB_ALTITUDE_TYPE values. More...
 
static const std::array< const std::string, 20 > mavros::utils::adsb_emitter_type_strings
 ADSB_EMITTER_TYPE values. More...
 
static const auto mavros::ftf::detail::AIRCRAFT_BASELINK_Q = quaternion_from_rpy(M_PI, 0.0, 0.0)
 Static quaternion needed for rotating between aircraft and base_link frames +PI rotation around X (Forward) axis transforms from Forward, Right, Down (aircraft) Fto Forward, Left, Up (base_link) frames. More...
 
static const auto mavros::ftf::detail::AIRCRAFT_BASELINK_R = AIRCRAFT_BASELINK_Q.normalized().toRotationMatrix()
 
std::atomic< uint8_t > mavros::UAS::autopilot
 
std::atomic< uint8_t > mavros::UAS::base_mode
 
std::vector< CapabilitiesCbmavros::UAS::capabilities_cb_vec
 
ros::Duration mavros::MavRos::conn_timeout
 
std::atomic< bool > mavros::UAS::connected
 
std::vector< ConnectionCbmavros::UAS::connection_cb_vec
 
diagnostic_updater::Updater mavros::UAS::diag_updater
 Mavros diagnostic updater. More...
 
std::shared_ptr< GeographicLib::Geoid > mavros::UAS::egm96_5
 Geoid dataset used to convert between AMSL and WGS-84. More...
 
std::atomic< uint64_t > mavros::UAS::fcu_capabilities
 
std::atomic< bool > mavros::UAS::fcu_caps_known
 
mavconn::MAVConnInterface::Ptr mavros::UAS::fcu_link
 MAVLink FCU device conection. More...
 
MavlinkDiag mavros::MavRos::fcu_link_diag
 
diagnostic_updater::Updater mavros::MavRos::gcs_diag_updater
 
mavconn::MAVConnInterface::Ptr mavros::MavRos::gcs_link
 
MavlinkDiag mavros::MavRos::gcs_link_diag
 
bool mavros::MavRos::gcs_quiet_mode
 
float mavros::UAS::gps_eph
 
float mavros::UAS::gps_epv
 
sensor_msgs::NavSatFix::Ptr mavros::UAS::gps_fix
 
int mavros::UAS::gps_fix_type
 
static const std::array< const std::string, 9 > mavros::utils::gps_fix_type_strings
 GPS_FIX_TYPE values. More...
 
int mavros::UAS::gps_satellites_visible
 
sensor_msgs::Imu::Ptr mavros::UAS::imu_enu_data
 
sensor_msgs::Imu::Ptr mavros::UAS::imu_ned_data
 
std::atomic< bool > mavros::MavlinkDiag::is_connected
 
static const std::array< const std::string, 4 > mavros::utils::landing_target_type_strings
 LANDING_TARGET_TYPE values. More...
 
unsigned int mavros::MavlinkDiag::last_drop_count
 
ros::Time mavros::MavRos::last_message_received_from_gcs
 
std::vector< plugin::PluginBase::Ptrmavros::MavRos::loaded_plugins
 
static const std::array< const std::string, 20 > mavros::utils::mav_autopilot_strings
 MAV_AUTOPILOT values. More...
 
static const std::unordered_map< typename std::underlying_type< MAV_COMPONENT >::type, const std::string > mavros::utils::mav_comp_id_strings
 
static const std::array< const std::string, 5 > mavros::utils::mav_distance_sensor_strings
 MAV_DISTANCE_SENSOR values. More...
 
static const std::array< const std::string, 9 > mavros::utils::mav_estimator_type_strings
 MAV_ESTIMATOR_TYPE values. More...
 
static const std::array< const std::string, 22 > mavros::utils::mav_frame_strings
 MAV_FRAME values. More...
 
static const std::array< const std::string, 16 > mavros::utils::mav_mission_result_strings
 MAV_MISSION_RESULT values. More...
 
static const std::array< const std::string, 9 > mavros::utils::mav_state_strings
 MAV_STATE values. More...
 
static const std::array< const std::string, 36 > mavros::utils::mav_type_names
 MAV_TYPE values. More...
 
static const std::array< const std::string, 36 > mavros::utils::mav_type_strings
 MAV_TYPE values. More...
 
UAS mavros::MavRos::mav_uas
 UAS object passed to all plugins. More...
 
ros::NodeHandle mavros::MavRos::mavlink_nh
 
ros::Publisher mavros::MavRos::mavlink_pub
 
ros::Subscriber mavros::MavRos::mavlink_sub
 
std::recursive_mutex mavros::UAS::mutex
 
static const auto mavros::ftf::detail::NED_ENU_Q = quaternion_from_rpy(M_PI, 0.0, M_PI_2)
 Static quaternion needed for rotating between ENU and NED frames NED to ENU: +PI/2 rotation about Z (Down) followed by a +PI rotation around X (old North/new East) ENU to NED: +PI/2 rotation about Z (Up) followed by a +PI rotation about X (old East/new North) More...
 
static const auto mavros::ftf::detail::NED_ENU_R = NED_ENU_Q.normalized().toRotationMatrix()
 3-D matrices to fill 6-D rotation matrix applied to change covariance matrices coordinate frames More...
 
pluginlib::ClassLoader< plugin::PluginBasemavros::MavRos::plugin_loader
 
std::unordered_map< mavlink::msgid_t, plugin::PluginBase::Subscriptionsmavros::MavRos::plugin_subscriptions
 FCU link -> router -> plugin handler. More...
 
static const std::unordered_map< typename std::underlying_type< MAV_SENSOR_ORIENTATION >::type, const OrientationPairmavros::utils::sensor_orientations
 
uint8_t mavros::UAS::target_component
 
uint8_t mavros::UAS::target_system
 
tf2_ros::TransformBroadcaster mavros::UAS::tf2_broadcaster
 
tf2_ros::Buffer mavros::UAS::tf2_buffer
 
tf2_ros::TransformListener mavros::UAS::tf2_listener
 
tf2_ros::StaticTransformBroadcaster mavros::UAS::tf2_static_broadcaster
 
std::atomic< uint64_t > mavros::UAS::time_offset
 
static const std::array< const std::string, 4 > mavros::utils::timesync_mode_strings
 timesync_mode values More...
 
timesync_mode mavros::UAS::tsync_mode
 
std::atomic< uint8_t > mavros::UAS::type
 
mavconn::MAVConnInterface::WeakPtr mavros::MavlinkDiag::weak_link
 

Detailed Description

MAVROS node implementation.

Macro Definition Documentation

◆ UAS_DIAG

#define UAS_DIAG (   uasobjptr)    ((uasobjptr)->diag_updater)

helper accessor to diagnostic updater

Definition at line 48 of file mavros_uas.h.

◆ UAS_FCU

#define UAS_FCU (   uasobjptr)    ((uasobjptr)->fcu_link)

helper accessor to FCU link interface

Definition at line 42 of file mavros_uas.h.

Typedef Documentation

◆ CapabilitiesCb

using mavros::UAS::CapabilitiesCb = std::function<void(MAV_CAP)>

Definition at line 79 of file mavros_uas.h.

◆ ConnectionCb

using mavros::UAS::ConnectionCb = std::function<void(bool)>

Definition at line 78 of file mavros_uas.h.

◆ Covariance3d

using mavros::ftf::Covariance3d = typedef sensor_msgs::Imu::_angular_velocity_covariance_type

Type matching rosmsg for 3x3 covariance matrix.

Definition at line 37 of file frame_tf.h.

◆ Covariance6d

using mavros::ftf::Covariance6d = typedef geometry_msgs::PoseWithCovariance::_covariance_type

Type matching rosmsg for 6x6 covariance matrix.

Definition at line 40 of file frame_tf.h.

◆ Covariance9d

using mavros::ftf::Covariance9d = typedef boost::array<double, 81>

Type matching rosmsg for 9x9 covariance matrix.

Definition at line 43 of file frame_tf.h.

◆ EigenMapConstCovariance3d

using mavros::ftf::EigenMapConstCovariance3d = typedef Eigen::Map<const Eigen::Matrix<double, 3, 3, Eigen::RowMajor> >

Definition at line 47 of file frame_tf.h.

◆ EigenMapConstCovariance6d

using mavros::ftf::EigenMapConstCovariance6d = typedef Eigen::Map<const Eigen::Matrix<double, 6, 6, Eigen::RowMajor> >

Definition at line 51 of file frame_tf.h.

◆ EigenMapConstCovariance9d

using mavros::ftf::EigenMapConstCovariance9d = typedef Eigen::Map<const Eigen::Matrix<double, 9, 9, Eigen::RowMajor> >

Definition at line 55 of file frame_tf.h.

◆ EigenMapCovariance3d

using mavros::ftf::EigenMapCovariance3d = typedef Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor> >

Eigen::Map for Covariance3d.

Definition at line 46 of file frame_tf.h.

◆ EigenMapCovariance6d

using mavros::ftf::EigenMapCovariance6d = typedef Eigen::Map<Eigen::Matrix<double, 6, 6, Eigen::RowMajor> >

Eigen::Map for Covariance6d.

Definition at line 50 of file frame_tf.h.

◆ EigenMapCovariance9d

using mavros::ftf::EigenMapCovariance9d = typedef Eigen::Map<Eigen::Matrix<double, 9, 9, Eigen::RowMajor> >

Eigen::Map for Covariance9d.

Definition at line 54 of file frame_tf.h.

◆ lock_guard

using mavros::UAS::lock_guard = std::lock_guard<std::recursive_mutex>

Definition at line 80 of file mavros_uas.h.

◆ Matrix6d

using mavros::ftf::detail::Matrix6d = typedef Eigen::Matrix<double, 6, 6>

Auxiliar matrices to Covariance transforms.

Definition at line 71 of file ftf_frame_conversions.cpp.

◆ Matrix9d

using mavros::ftf::detail::Matrix9d = typedef Eigen::Matrix<double, 9, 9>

Definition at line 72 of file ftf_frame_conversions.cpp.

◆ MAV_AUTOPILOT

using mavros::UAS::MAV_AUTOPILOT = mavlink::minimal::MAV_AUTOPILOT

Definition at line 71 of file mavros_uas.h.

◆ MAV_CAP

using mavros::UAS::MAV_CAP = mavlink::common::MAV_PROTOCOL_CAPABILITY

Definition at line 74 of file mavros_uas.h.

◆ MAV_MODE_FLAG

using mavros::UAS::MAV_MODE_FLAG = mavlink::minimal::MAV_MODE_FLAG

Definition at line 72 of file mavros_uas.h.

◆ MAV_STATE

using mavros::UAS::MAV_STATE = mavlink::minimal::MAV_STATE

Definition at line 73 of file mavros_uas.h.

◆ MAV_TYPE

using mavros::UAS::MAV_TYPE = mavlink::minimal::MAV_TYPE

Definition at line 70 of file mavros_uas.h.

◆ OrientationPair

using mavros::utils::OrientationPair = typedef std::pair<const std::string, const Eigen::Quaterniond>

Definition at line 28 of file enum_sensor_orientation.cpp.

◆ timesync_mode

Definition at line 75 of file mavros_uas.h.

◆ unique_lock

using mavros::UAS::unique_lock = std::unique_lock<std::recursive_mutex>

Definition at line 81 of file mavros_uas.h.

Enumeration Type Documentation

◆ StaticEcefTF

Orientation transform options when applying rotations to data, for ECEF.

Enumerator
ECEF_TO_ENU 

change from expressed WRT ECEF frame to WRT ENU frame

ENU_TO_ECEF 

change from expressed WRT ENU frame to WRT ECEF frame

Definition at line 72 of file frame_tf.h.

◆ StaticTF

enum mavros::ftf::StaticTF
strong

Orientation transform options when applying rotations to data.

Enumerator
NED_TO_ENU 

will change orientation from being expressed WRT NED frame to WRT ENU frame

ENU_TO_NED 

change from expressed WRT ENU frame to WRT NED frame

AIRCRAFT_TO_BASELINK 

change from expressed WRT aircraft frame to WRT to baselink frame

BASELINK_TO_AIRCRAFT 

change from expressed WRT baselnk to WRT aircraft

ABSOLUTE_FRAME_AIRCRAFT_TO_BASELINK 

change orientation from being expressed in aircraft frame to baselink frame in an absolute frame of reference.

ABSOLUTE_FRAME_BASELINK_TO_AIRCRAFT 

change orientation from being expressed in baselink frame to aircraft frame in an absolute frame of reference

Definition at line 60 of file frame_tf.h.

Function Documentation

◆ add_capabilities_change_handler()

void UAS::add_capabilities_change_handler ( UAS::CapabilitiesCb  cb)

Adds a function to the capabilities callback queue.

Parameters
cbA void function that takes a single mavlink::common::MAV_PROTOCOL_CAPABILITY(MAV_CAP) param

Definition at line 133 of file uas_data.cpp.

◆ add_connection_change_handler()

void UAS::add_connection_change_handler ( UAS::ConnectionCb  cb)

Add connection change handler callback.

Definition at line 83 of file uas_data.cpp.

◆ add_plugin()

void MavRos::add_plugin ( std::string &  pl_name,
ros::V_string blacklist,
ros::V_string whitelist 
)
private

load plugin

Loads plugin (if not blacklisted)

Definition at line 316 of file mavros.cpp.

◆ add_static_transform()

void UAS::add_static_transform ( const std::string &  frame_id,
const std::string &  child_id,
const Eigen::Affine3d &  tr,
std::vector< geometry_msgs::TransformStamped > &  vector 
)

Add static transform. To publish all static transforms at once, we stack them in a std::vector.

Stack static transform into vector.

Parameters
frame_idparent frame for transform
child_idchild frame for transform
trtransform
vectorvector of transforms

Definition at line 254 of file uas_data.cpp.

◆ AIRCRAFT_BASELINK_AFFINE()

static const Eigen::Affine3d mavros::ftf::detail::AIRCRAFT_BASELINK_AFFINE ( AIRCRAFT_BASELINK_Q  )
static

Static vector needed for rotating between aircraft and base_link frames +PI rotation around X (Forward) axis transforms from Forward, Right, Down (aircraft) Fto Forward, Left, Up (base_link) frames.

◆ cmode_from_str()

bool UAS::cmode_from_str ( std::string  cmode_str,
uint32_t &  custom_mode 
)

Lookup custom mode for given string.

Complimentary to str_mode_v10()

Parameters
[in]cmode_strstring representation of mode
[out]custom_modedecoded value
Returns
true if success

Definition at line 254 of file uas_stringify.cpp.

◆ covariance_to_mavlink()

template<class T , std::size_t SIZE>
void mavros::ftf::covariance_to_mavlink ( const T &  cov,
std::array< float, SIZE > &  covmsg 
)
inline

Convert covariance matrix to MAVLink float[n] format.

Definition at line 393 of file frame_tf.h.

◆ covariance_urt_to_mavlink()

template<class T , std::size_t ARR_SIZE>
void mavros::ftf::covariance_urt_to_mavlink ( const T &  covmap,
std::array< float, ARR_SIZE > &  covmsg 
)
inline

Convert upper right triangular of a covariance matrix to MAVLink float[n] format.

Definition at line 402 of file frame_tf.h.

◆ ellipsoid_to_geoid_height()

template<class T >
double mavros::UAS::ellipsoid_to_geoid_height ( lla)
inline

Conversion from height above ellipsoid (WGS-84) to height above geoid (AMSL)

Definition at line 263 of file mavros_uas.h.

◆ geoid_to_ellipsoid_height()

template<class T >
double mavros::UAS::geoid_to_ellipsoid_height ( lla)
inline

Conversion from height above geoid (AMSL) to height above ellipsoid (WGS-84)

Definition at line 250 of file mavros_uas.h.

◆ get_armed()

bool mavros::UAS::get_armed ( )
inline

Returns arming status.

Note
There may be race condition between SET_MODE and HEARTBEAT.

Definition at line 141 of file mavros_uas.h.

◆ get_attitude_angular_velocity_enu()

geometry_msgs::Vector3 UAS::get_attitude_angular_velocity_enu ( )

Get angular velocity from IMU data.

Returns
vector3 [ENU]

Definition at line 191 of file uas_data.cpp.

◆ get_attitude_angular_velocity_ned()

geometry_msgs::Vector3 UAS::get_attitude_angular_velocity_ned ( )

Get angular velocity from IMU data.

Returns
vector3 [NED]

Definition at line 204 of file uas_data.cpp.

◆ get_attitude_imu_enu()

sensor_msgs::Imu::Ptr UAS::get_attitude_imu_enu ( )

Get IMU data [ENU].

Definition at line 153 of file uas_data.cpp.

◆ get_attitude_imu_ned()

sensor_msgs::Imu::Ptr UAS::get_attitude_imu_ned ( )

Get IMU data [NED].

Definition at line 159 of file uas_data.cpp.

◆ get_attitude_orientation_enu()

geometry_msgs::Quaternion UAS::get_attitude_orientation_enu ( )

Get Attitude orientation quaternion.

Returns
orientation quaternion [ENU]

Definition at line 165 of file uas_data.cpp.

◆ get_attitude_orientation_ned()

geometry_msgs::Quaternion UAS::get_attitude_orientation_ned ( )

Get Attitude orientation quaternion.

Returns
orientation quaternion [NED]

Definition at line 178 of file uas_data.cpp.

◆ get_autopilot()

MAV_AUTOPILOT mavros::UAS::get_autopilot ( )
inline

Returns autopilot type.

Definition at line 131 of file mavros_uas.h.

◆ get_capabilities()

uint64_t UAS::get_capabilities ( )

Definition at line 97 of file uas_data.cpp.

◆ get_gps_epts()

void UAS::get_gps_epts ( float eph,
float epv,
int fix_type,
int satellites_visible 
)

Returns EPH, EPV, Fix type and satellites visible.

Definition at line 234 of file uas_data.cpp.

◆ get_gps_fix()

sensor_msgs::NavSatFix::Ptr UAS::get_gps_fix ( )

Retunrs last GPS RAW message.

Definition at line 245 of file uas_data.cpp.

◆ get_hil_state()

bool mavros::UAS::get_hil_state ( )
inline

Returns HIL status.

Definition at line 149 of file mavros_uas.h.

◆ get_tgt_component()

uint8_t mavros::UAS::get_tgt_component ( )
inline

Return communication target component.

Definition at line 166 of file mavros_uas.h.

◆ get_tgt_system()

uint8_t mavros::UAS::get_tgt_system ( )
inline

Return communication target system.

Definition at line 159 of file mavros_uas.h.

◆ get_time_offset()

uint64_t mavros::UAS::get_time_offset ( void  )
inline

Definition at line 303 of file mavros_uas.h.

◆ get_timesync_mode()

timesync_mode mavros::UAS::get_timesync_mode ( void  )
inline

Definition at line 311 of file mavros_uas.h.

◆ get_type()

MAV_TYPE mavros::UAS::get_type ( )
inline

Returns vehicle type.

Definition at line 123 of file mavros_uas.h.

◆ has_capabilities()

template<typename ... Ts>
bool mavros::UAS::has_capabilities ( Ts ...  capabilities)
inline

Function to check if the flight controller has a set of capabilities.

Parameters
capabilitiescan accept a multiple capability params either in enum or int from

Definition at line 336 of file mavros_uas.h.

◆ has_capability()

template<typename T >
bool mavros::UAS::has_capability ( capability)
inline

Function to check if the flight controller has a capability.

Parameters
capabilitiescan accept a multiple capability params either in enum or int from

Definition at line 324 of file mavros_uas.h.

◆ is_ardupilotmega()

bool mavros::UAS::is_ardupilotmega ( )
inline

Check that FCU is APM.

Definition at line 410 of file mavros_uas.h.

◆ is_connected()

bool mavros::UAS::is_connected ( )
inline

Return connection status.

Definition at line 99 of file mavros_uas.h.

◆ is_my_target() [1/2]

bool mavros::UAS::is_my_target ( uint8_t  sysid,
uint8_t  compid 
)
inline

Check that sys/comp id's is my target.

Definition at line 396 of file mavros_uas.h.

◆ is_my_target() [2/2]

bool mavros::UAS::is_my_target ( uint8_t  sysid)
inline

Check that system id is my target.

Definition at line 403 of file mavros_uas.h.

◆ is_px4()

bool mavros::UAS::is_px4 ( )
inline

Check that FCU is PX4.

Definition at line 417 of file mavros_uas.h.

◆ log_connect_change()

void MavRos::log_connect_change ( bool  connected)
private

Definition at line 394 of file mavros.cpp.

◆ make_orientation()

static const OrientationPair mavros::utils::make_orientation ( const std::string &  name,
const double  roll,
const double  pitch,
const double  yaw 
)
static

Definition at line 31 of file enum_sensor_orientation.cpp.

◆ mavlink_pub_cb()

void MavRos::mavlink_pub_cb ( const mavlink::mavlink_message_t mmsg,
const mavconn::Framing  framing 
)
private

fcu link -> ros

Definition at line 232 of file mavros.cpp.

◆ mavlink_sub_cb()

void MavRos::mavlink_sub_cb ( const mavros_msgs::Mavlink::ConstPtr rmsg)
private

ros -> fcu link

Definition at line 244 of file mavros.cpp.

◆ mavlink_to_quaternion()

Eigen::Quaterniond mavros::ftf::mavlink_to_quaternion ( const std::array< float, 4 > &  q)
inline

Convert Mavlink float[4] quaternion to Eigen.

Definition at line 384 of file frame_tf.h.

◆ mavlink_urt_to_covariance_matrix()

template<class T , std::size_t ARR_SIZE>
void mavros::ftf::mavlink_urt_to_covariance_matrix ( const std::array< float, ARR_SIZE > &  covmsg,
T &  covmat 
)
inline

Convert MAVLink float[n] format (upper right triangular of a covariance matrix) to Eigen::MatrixXd<n,n> full covariance matrix.

Definition at line 423 of file frame_tf.h.

◆ MavlinkDiag()

MavlinkDiag::MavlinkDiag ( std::string  name)
explicit

Definition at line 18 of file mavlink_diag.cpp.

◆ MavRos()

MavRos::MavRos ( )

Definition at line 34 of file mavros.cpp.

◆ msg_set_target()

template<typename _T >
void mavros::UAS::msg_set_target ( _T &  msg)
inline

Helper template to set target id's of message.

Definition at line 388 of file mavros_uas.h.

◆ NED_ENU_AFFINE()

static const Eigen::Affine3d mavros::ftf::detail::NED_ENU_AFFINE ( NED_ENU_Q  )
static

Static vector needed for rotating between ENU and NED frames +PI rotation around X (North) axis follwed by +PI/2 rotation about Z (Down) gives the ENU frame. Similarly, a +PI rotation about X (East) followed by a +PI/2 roation about Z (Up) gives the NED frame.

◆ NED_ENU_REFLECTION_XY()

static const Eigen::PermutationMatrix<3> mavros::ftf::detail::NED_ENU_REFLECTION_XY ( Eigen::Vector3i(1, 0, 2)  )
static

Use reflections instead of rotations for NED <-> ENU transformation to avoid NaN/Inf floating point pollution across different axes since in NED <-> ENU the axes are perfectly aligned.

◆ NED_ENU_REFLECTION_Z()

static const Eigen::DiagonalMatrix<double,3> mavros::ftf::detail::NED_ENU_REFLECTION_Z ( ,
,
1 
)
static

◆ plugin_route_cb()

void MavRos::plugin_route_cb ( const mavlink::mavlink_message_t mmsg,
const mavconn::Framing  framing 
)
private

message router

Definition at line 254 of file mavros.cpp.

◆ publish_static_transform()

void UAS::publish_static_transform ( const std::string &  frame_id,
const std::string &  child_id,
const Eigen::Affine3d &  tr 
)

Publishes static transform.

Parameters
frame_idparent frame for transform
child_idchild frame for transform
trtransform

Definition at line 267 of file uas_data.cpp.

◆ quaternion_from_rpy() [1/2]

Eigen::Quaterniond mavros::ftf::quaternion_from_rpy ( const Eigen::Vector3d &  rpy)

Convert euler angles to quaternion.

Definition at line 27 of file ftf_quaternion_utils.cpp.

◆ quaternion_from_rpy() [2/2]

Eigen::Quaterniond mavros::ftf::quaternion_from_rpy ( const double  roll,
const double  pitch,
const double  yaw 
)
inline

Convert euler angles to quaternion.

Returns
quaternion, same as tf::quaternionFromRPY() but in Eigen format.

Definition at line 337 of file frame_tf.h.

◆ quaternion_get_yaw()

double mavros::ftf::quaternion_get_yaw ( const Eigen::Quaterniond &  q)

Get Yaw angle from quaternion.

Replacement function for tf::getYaw()

Definition at line 43 of file ftf_quaternion_utils.cpp.

◆ quaternion_to_mavlink()

template<typename _Scalar , typename std::enable_if< std::is_floating_point< _Scalar >::value, bool >::type = true>
void mavros::ftf::quaternion_to_mavlink ( const Eigen::Quaternion< _Scalar > &  q,
std::array< float, 4 > &  qmsg 
)
inline

Store Quaternion to MAVLink float[4] format.

MAVLink uses wxyz order, wile Eigen::Quaterniond uses xyzw internal order, so it can't be stored to array using Eigen::Map.

Definition at line 373 of file frame_tf.h.

◆ quaternion_to_rpy() [1/2]

Eigen::Vector3d mavros::ftf::quaternion_to_rpy ( const Eigen::Quaterniond &  q)

Convert quaternion to euler angles.

Reverse operation to quaternion_from_rpy()

Definition at line 37 of file ftf_quaternion_utils.cpp.

◆ quaternion_to_rpy() [2/2]

void mavros::ftf::quaternion_to_rpy ( const Eigen::Quaterniond &  q,
double &  roll,
double &  pitch,
double &  yaw 
)
inline

Convert quaternion to euler angles.

Definition at line 351 of file frame_tf.h.

◆ run()

void MavlinkDiag::run ( diagnostic_updater::DiagnosticStatusWrapper stat)
virtual

Implements diagnostic_updater::DiagnosticTask.

Definition at line 24 of file mavlink_diag.cpp.

◆ sensor_orientation_matching()

Eigen::Quaterniond mavros::utils::sensor_orientation_matching ( MAV_SENSOR_ORIENTATION  orientation)

Definition at line 137 of file enum_sensor_orientation.cpp.

◆ set_connection_status()

void mavros::MavlinkDiag::set_connection_status ( bool  connected)
inline

Definition at line 34 of file mavlink_diag.h.

◆ set_mavconn()

void mavros::MavlinkDiag::set_mavconn ( const mavconn::MAVConnInterface::Ptr link)
inline

Definition at line 30 of file mavlink_diag.h.

◆ set_tgt()

void mavros::UAS::set_tgt ( uint8_t  sys,
uint8_t  comp 
)
inline

Definition at line 170 of file mavros_uas.h.

◆ set_time_offset()

void mavros::UAS::set_time_offset ( uint64_t  offset_ns)
inline

Definition at line 299 of file mavros_uas.h.

◆ set_timesync_mode()

void mavros::UAS::set_timesync_mode ( timesync_mode  mode)
inline

Definition at line 307 of file mavros_uas.h.

◆ spin()

void MavRos::spin ( )

Definition at line 189 of file mavros.cpp.

◆ startup_px4_usb_quirk()

void MavRos::startup_px4_usb_quirk ( )
private

start mavlink app on USB

Definition at line 382 of file mavros.cpp.

◆ str_mode_v10()

std::string UAS::str_mode_v10 ( uint8_t  base_mode,
uint32_t  custom_mode 
)

Represent FCU mode as string.

Port pymavlink mavutil.mode_string_v10

Supported FCU's:

  • APM:Plane
  • APM:Copter
  • PX4
Parameters
[in]base_modebase mode
[in]custom_modecustom mode data

Definition at line 189 of file uas_stringify.cpp.

◆ synchronise_stamp() [1/2]

ros::Time UAS::synchronise_stamp ( uint32_t  time_boot_ms)

Compute FCU message time from time_boot_ms or time_usec field.

Uses time_offset for calculation

Returns
FCU time if it is known else current wall time.

Definition at line 32 of file uas_timesync.cpp.

◆ synchronise_stamp() [2/2]

ros::Time UAS::synchronise_stamp ( uint64_t  time_usec)

Definition at line 44 of file uas_timesync.cpp.

◆ synchronized_header()

template<typename T >
std_msgs::Header mavros::UAS::synchronized_header ( const std::string &  frame_id,
const T  time_stamp 
)
inline

Create message header from time_boot_ms or time_usec stamps and frame_id.

Setting frame_id and stamp are pretty common, this little helper should reduce LOC.

Parameters
[in]frame_idframe for header
[in]time_stampmavlink message time
Returns
Header with syncronized stamp and frame id

Definition at line 375 of file mavros_uas.h.

◆ to_eigen() [1/3]

Eigen::Vector3d mavros::ftf::to_eigen ( const geometry_msgs::Point  r)
inline

Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.

Definition at line 452 of file frame_tf.h.

◆ to_eigen() [2/3]

Eigen::Vector3d mavros::ftf::to_eigen ( const geometry_msgs::Vector3  r)
inline

Helper to convert common ROS geometry_msgs::Vector3 to Eigen::Vector3d.

Definition at line 456 of file frame_tf.h.

◆ to_eigen() [3/3]

Eigen::Quaterniond mavros::ftf::to_eigen ( const geometry_msgs::Quaternion  r)
inline

Helper to convert common ROS geometry_msgs::Quaternion to Eigen::Quaterniond.

Definition at line 460 of file frame_tf.h.

◆ to_name()

std::string mavros::utils::to_name ( MAV_TYPE  e)

Definition at line 249 of file enum_to_string.cpp.

◆ to_string() [1/13]

std::string mavros::utils::to_string ( MAV_SENSOR_ORIENTATION  orientation)

Definition at line 124 of file enum_sensor_orientation.cpp.

◆ to_string() [2/13]

std::string mavros::utils::to_string ( MAV_AUTOPILOT  e)

Definition at line 131 of file enum_to_string.cpp.

◆ to_string() [3/13]

std::string mavros::utils::to_string ( MAV_TYPE  e)

Definition at line 195 of file enum_to_string.cpp.

◆ to_string() [4/13]

std::string mavros::utils::to_string ( MAV_STATE  e)

Definition at line 286 of file enum_to_string.cpp.

◆ to_string() [5/13]

std::string mavros::utils::to_string ( ADSB_ALTITUDE_TYPE  e)

Definition at line 349 of file enum_to_string.cpp.

◆ to_string() [6/13]

std::string mavros::utils::to_string ( ADSB_EMITTER_TYPE  e)

Definition at line 387 of file enum_to_string.cpp.

◆ to_string() [7/13]

std::string mavros::utils::to_string ( MAV_ESTIMATOR_TYPE  e)

Definition at line 414 of file enum_to_string.cpp.

◆ to_string() [8/13]

std::string mavros::utils::to_string ( GPS_FIX_TYPE  e)

Definition at line 441 of file enum_to_string.cpp.

◆ to_string() [9/13]

std::string mavros::utils::to_string ( MAV_MISSION_RESULT  e)

Definition at line 485 of file enum_to_string.cpp.

◆ to_string() [10/13]

std::string mavros::utils::to_string ( MAV_FRAME  e)

Definition at line 525 of file enum_to_string.cpp.

◆ to_string() [11/13]

std::string mavros::utils::to_string ( MAV_COMPONENT  e)

Definition at line 682 of file enum_to_string.cpp.

◆ to_string() [12/13]

std::string mavros::utils::to_string ( MAV_DISTANCE_SENSOR  e)

Definition at line 731 of file enum_to_string.cpp.

◆ to_string() [13/13]

std::string mavros::utils::to_string ( LANDING_TARGET_TYPE  e)

Definition at line 753 of file enum_to_string.cpp.

◆ transform_frame() [1/4]

Eigen::Vector3d mavros::ftf::detail::transform_frame ( const Eigen::Vector3d &  vec,
const Eigen::Quaterniond &  q 
)

Transform data expressed in one frame to another frame.

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 258 of file ftf_frame_conversions.cpp.

◆ transform_frame() [2/4]

Covariance3d mavros::ftf::detail::transform_frame ( const Covariance3d cov,
const Eigen::Quaterniond &  q 
)

Transform 3x3 convariance expressed in one frame to another.

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 264 of file ftf_frame_conversions.cpp.

◆ transform_frame() [3/4]

Covariance6d mavros::ftf::detail::transform_frame ( const Covariance6d cov,
const Eigen::Quaterniond &  q 
)

Transform 6x6 convariance expressed in one frame to another.

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 274 of file ftf_frame_conversions.cpp.

◆ transform_frame() [4/4]

Covariance9d mavros::ftf::detail::transform_frame ( const Covariance9d cov,
const Eigen::Quaterniond &  q 
)

Transform 9x9 convariance expressed in one frame to another.

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 289 of file ftf_frame_conversions.cpp.

◆ transform_frame_aircraft_baselink()

template<class T >
T mavros::ftf::transform_frame_aircraft_baselink ( const T &  in)
inline

Transform data expressed in Aircraft frame to Baselink frame.

Definition at line 233 of file frame_tf.h.

◆ transform_frame_aircraft_enu()

template<class T >
T mavros::ftf::transform_frame_aircraft_enu ( const T &  in,
const Eigen::Quaterniond &  q 
)
inline

Transform data expressed in aircraft frame to ENU frame. Assumes quaternion represents rotation from aircraft frame to ENU frame.

Definition at line 293 of file frame_tf.h.

◆ transform_frame_aircraft_ned()

template<class T >
T mavros::ftf::transform_frame_aircraft_ned ( const T &  in,
const Eigen::Quaterniond &  q 
)
inline

Transform data expressed in aircraft frame to NED frame. Assumes quaternion represents rotation from aircraft frame to NED frame.

Definition at line 275 of file frame_tf.h.

◆ transform_frame_baselink_aircraft()

template<class T >
T mavros::ftf::transform_frame_baselink_aircraft ( const T &  in)
inline

Transform data expressed in Baselink frame to Aircraft frame.

Definition at line 242 of file frame_tf.h.

◆ transform_frame_baselink_enu()

template<class T >
T mavros::ftf::transform_frame_baselink_enu ( const T &  in,
const Eigen::Quaterniond &  q 
)
inline

Transform data expressed in baselink to ENU frame. Assumes quaternion represents rotation from basel_link to ENU frame.

Definition at line 320 of file frame_tf.h.

◆ transform_frame_ecef_enu()

template<class T >
T mavros::ftf::transform_frame_ecef_enu ( const T &  in,
const T &  map_origin 
)
inline

Transform data expressed in ECEF frame to ENU frame.

Parameters
inlocal ECEF coordinates [m]
map_origingeodetic origin [lla]
Returns
local ENU coordinates [m].

Definition at line 254 of file frame_tf.h.

◆ transform_frame_enu_aircraft()

template<class T >
T mavros::ftf::transform_frame_enu_aircraft ( const T &  in,
const Eigen::Quaterniond &  q 
)
inline

Transform data expressed in ENU to aircraft frame. Assumes quaternion represents rotation from ENU to aircraft frame.

Definition at line 302 of file frame_tf.h.

◆ transform_frame_enu_baselink()

template<class T >
T mavros::ftf::transform_frame_enu_baselink ( const T &  in,
const Eigen::Quaterniond &  q 
)
inline

Transform data expressed in ENU to base_link frame. Assumes quaternion represents rotation from ENU to base_link frame.

Definition at line 311 of file frame_tf.h.

◆ transform_frame_enu_ecef()

template<class T >
T mavros::ftf::transform_frame_enu_ecef ( const T &  in,
const T &  map_origin 
)
inline

Transform data expressed in ENU frame to ECEF frame.

Parameters
inlocal ENU coordinates [m]
map_origingeodetic origin [lla]
Returns
local ECEF coordinates [m].

Definition at line 266 of file frame_tf.h.

◆ transform_frame_enu_ned()

template<class T >
T mavros::ftf::transform_frame_enu_ned ( const T &  in)
inline

Transform data expressed in ENU to NED frame.

Definition at line 224 of file frame_tf.h.

◆ transform_frame_ned_aircraft()

template<class T >
T mavros::ftf::transform_frame_ned_aircraft ( const T &  in,
const Eigen::Quaterniond &  q 
)
inline

Transform data expressed in NED to aircraft frame. Assumes quaternion represents rotation from NED to aircraft frame.

Definition at line 284 of file frame_tf.h.

◆ transform_frame_ned_enu()

template<class T >
T mavros::ftf::transform_frame_ned_enu ( const T &  in)
inline

Transform data expressed in NED to ENU frame.

Definition at line 215 of file frame_tf.h.

◆ transform_orientation()

Eigen::Quaterniond mavros::ftf::detail::transform_orientation ( const Eigen::Quaterniond &  q,
const StaticTF  transform 
)

Transform representation of attitude from 1 frame to another (e.g. transfrom attitude from representing from base_link -> NED to representing base_link -> ENU)

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 75 of file ftf_frame_conversions.cpp.

◆ transform_orientation_absolute_frame_aircraft_baselink()

template<class T >
T mavros::ftf::transform_orientation_absolute_frame_aircraft_baselink ( const T &  in)
inline

Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame, treating aircraft frame as in an absolute frame of reference (local NED).

Definition at line 197 of file frame_tf.h.

◆ transform_orientation_absolute_frame_baselink_aircraft()

template<class T >
T mavros::ftf::transform_orientation_absolute_frame_baselink_aircraft ( const T &  in)
inline

Transform from attitude represented WRT baselink frame to attitude represented WRT body frame, treating baselink frame as in an absolute frame of reference (local NED).

Definition at line 207 of file frame_tf.h.

◆ transform_orientation_aircraft_baselink()

template<class T >
T mavros::ftf::transform_orientation_aircraft_baselink ( const T &  in)
inline

Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame.

Definition at line 178 of file frame_tf.h.

◆ transform_orientation_baselink_aircraft()

template<class T >
T mavros::ftf::transform_orientation_baselink_aircraft ( const T &  in)
inline

Transform from attitude represented WRT baselink frame to attitude represented WRT body frame.

Definition at line 187 of file frame_tf.h.

◆ transform_orientation_enu_ned()

template<class T >
T mavros::ftf::transform_orientation_enu_ned ( const T &  in)
inline

Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame.

Definition at line 169 of file frame_tf.h.

◆ transform_orientation_ned_enu()

template<class T >
T mavros::ftf::transform_orientation_ned_enu ( const T &  in)
inline

Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame.

Definition at line 160 of file frame_tf.h.

◆ transform_static_frame() [1/5]

Eigen::Vector3d mavros::ftf::detail::transform_static_frame ( const Eigen::Vector3d &  vec,
const StaticTF  transform 
)

Transform data expressed in one frame to another frame.

General function. Please use specialized variants.

Definition at line 100 of file ftf_frame_conversions.cpp.

◆ transform_static_frame() [2/5]

Covariance3d mavros::ftf::detail::transform_static_frame ( const Covariance3d cov,
const StaticTF  transform 
)

Transform 3d convariance expressed in one frame to another.

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 117 of file ftf_frame_conversions.cpp.

◆ transform_static_frame() [3/5]

Covariance6d mavros::ftf::detail::transform_static_frame ( const Covariance6d cov,
const StaticTF  transform 
)

Transform 6d convariance expressed in one frame to another.

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 141 of file ftf_frame_conversions.cpp.

◆ transform_static_frame() [4/5]

Covariance9d mavros::ftf::detail::transform_static_frame ( const Covariance9d cov,
const StaticTF  transform 
)

Transform 9d convariance expressed in one frame to another.

General function. Please use specialized enu-ned and ned-enu variants.

Definition at line 176 of file ftf_frame_conversions.cpp.

◆ transform_static_frame() [5/5]

Eigen::Vector3d mavros::ftf::detail::transform_static_frame ( const Eigen::Vector3d &  vec,
const Eigen::Vector3d &  map_origin,
const StaticEcefTF  transform 
)

Transform data expressed in one frame to another frame with additional map origin parameter.

General function. Please use specialized variants.

Degrees to radians

Compute transform from ECEF to ENU: http://www.navipedia.net/index.php/Transformations_between_ECEF_and_ENU_coordinates ϕ = latitude λ = longitude The rotation is composed by a counter-clockwise rotation over the Z-axis by an angle of 90 + λ followed by a counter-clockwise rotation over the east-axis by an angle of 90 - ϕ. R = [-sinλ cosλ 0.0 -cosλ*sinϕ -sinλ*sinϕ cosϕ cosλ*cosϕ sinλ*cosϕ sinϕ ] [East, North, Up] = R * [∂x, ∂y, ∂z] where both [East, North, Up] and [∂x, ∂y, ∂z] are local coordinates relative to map origin.

Degrees to radians

Compute transform from ECEF to ENU: http://www.navipedia.net/index.php/Transformations_between_ECEF_and_ENU_coordinates ϕ = latitude λ = longitude The rotation is composed by a counter-clockwise rotation over the Z-axis by an angle of 90 + λ followed by a counter-clockwise rotation over the east-axis by an angle of 90 - ϕ. R = [-sinλ cosλ 0.0 -cosλ*sinϕ -sinλ*sinϕ cosϕ cosλ*cosϕ sinλ*cosϕ sinϕ ] [East, North, Up] = R * [∂x, ∂y, ∂z] where both [East, North, Up] and [∂x, ∂y, ∂z] are local coordinates relative to map origin.

Definition at line 213 of file ftf_frame_conversions.cpp.

◆ UAS()

UAS::UAS ( )

Definition at line 24 of file uas_data.cpp.

◆ update_attitude_imu_enu()

void UAS::update_attitude_imu_enu ( sensor_msgs::Imu::Ptr imu)

Store IMU data [ENU].

Definition at line 141 of file uas_data.cpp.

◆ update_attitude_imu_ned()

void UAS::update_attitude_imu_ned ( sensor_msgs::Imu::Ptr imu)

Store IMU data [NED].

Definition at line 147 of file uas_data.cpp.

◆ update_capabilities()

void UAS::update_capabilities ( bool  known,
uint64_t  caps = 0 
)

Update the capabilities if they've changed every VERSION/timeout.

Definition at line 109 of file uas_data.cpp.

◆ update_connection_status()

void UAS::update_connection_status ( bool  conn_)

Update autopilot connection status (every HEARTBEAT/conn_timeout)

Definition at line 72 of file uas_data.cpp.

◆ update_gps_fix_epts()

void UAS::update_gps_fix_epts ( sensor_msgs::NavSatFix::Ptr fix,
float  eph,
float  epv,
int  fix_type,
int  satellites_visible 
)

Store GPS RAW data.

Definition at line 220 of file uas_data.cpp.

◆ update_heartbeat()

void UAS::update_heartbeat ( uint8_t  type_,
uint8_t  autopilot_,
uint8_t  base_mode_ 
)

Update autopilot type on every HEARTBEAT

Definition at line 65 of file uas_data.cpp.

◆ ~MavRos()

mavros::MavRos::~MavRos ( )
inline

Definition at line 38 of file mavros.h.

◆ ~UAS()

mavros::UAS::~UAS ( )
inline

Definition at line 84 of file mavros_uas.h.

Variable Documentation

◆ adsb_altitude_type_strings

const std::array<const std::string, 2> mavros::utils::adsb_altitude_type_strings
static
Initial value:
{{
"PRESSURE_QNH",
"GEOMETRIC",
}}

ADSB_ALTITUDE_TYPE values.

Definition at line 344 of file enum_to_string.cpp.

◆ adsb_emitter_type_strings

const std::array<const std::string, 20> mavros::utils::adsb_emitter_type_strings
static
Initial value:
{{
"NO_INFO",
"LIGHT",
"SMALL",
"LARGE",
"HIGH_VORTEX_LARGE",
"HEAVY",
"HIGHLY_MANUV",
"ROTOCRAFT",
"UNASSIGNED",
"GLIDER",
"LIGHTER_AIR",
"PARACHUTE",
"ULTRA_LIGHT",
"UNASSIGNED2",
"UAV",
"SPACE",
"UNASSGINED3",
"EMERGENCY_SURFACE",
"SERVICE_SURFACE",
"POINT_OBSTACLE",
}}

ADSB_EMITTER_TYPE values.

Definition at line 364 of file enum_to_string.cpp.

◆ AIRCRAFT_BASELINK_Q

const auto mavros::ftf::detail::AIRCRAFT_BASELINK_Q = quaternion_from_rpy(M_PI, 0.0, 0.0)
static

Static quaternion needed for rotating between aircraft and base_link frames +PI rotation around X (Forward) axis transforms from Forward, Right, Down (aircraft) Fto Forward, Left, Up (base_link) frames.

Definition at line 37 of file ftf_frame_conversions.cpp.

◆ AIRCRAFT_BASELINK_R

const auto mavros::ftf::detail::AIRCRAFT_BASELINK_R = AIRCRAFT_BASELINK_Q.normalized().toRotationMatrix()
static

Definition at line 58 of file ftf_frame_conversions.cpp.

◆ autopilot

std::atomic<uint8_t> mavros::UAS::autopilot
private

Definition at line 451 of file mavros_uas.h.

◆ base_mode

std::atomic<uint8_t> mavros::UAS::base_mode
private

Definition at line 452 of file mavros_uas.h.

◆ capabilities_cb_vec

std::vector<CapabilitiesCb> mavros::UAS::capabilities_cb_vec
private

Definition at line 459 of file mavros_uas.h.

◆ conn_timeout

ros::Duration mavros::MavRos::conn_timeout
private

Definition at line 48 of file mavros.h.

◆ connected

std::atomic<bool> mavros::UAS::connected
private

Definition at line 457 of file mavros_uas.h.

◆ connection_cb_vec

std::vector<ConnectionCb> mavros::UAS::connection_cb_vec
private

Definition at line 458 of file mavros_uas.h.

◆ diag_updater

diagnostic_updater::Updater mavros::UAS::diag_updater

Mavros diagnostic updater.

Definition at line 94 of file mavros_uas.h.

◆ egm96_5

std::shared_ptr<GeographicLib::Geoid> mavros::UAS::egm96_5

Geoid dataset used to convert between AMSL and WGS-84.

That class loads egm96_5 dataset to RAM, it is about 24 MiB.

Definition at line 243 of file mavros_uas.h.

◆ fcu_capabilities

std::atomic<uint64_t> mavros::UAS::fcu_capabilities
private

Definition at line 474 of file mavros_uas.h.

◆ fcu_caps_known

std::atomic<bool> mavros::UAS::fcu_caps_known
private

Definition at line 473 of file mavros_uas.h.

◆ fcu_link

mavconn::MAVConnInterface::Ptr mavros::UAS::fcu_link

MAVLink FCU device conection.

Definition at line 84 of file mavros_uas.h.

◆ fcu_link_diag

MavlinkDiag mavros::MavRos::fcu_link_diag
private

Definition at line 54 of file mavros.h.

◆ gcs_diag_updater

diagnostic_updater::Updater mavros::MavRos::gcs_diag_updater
private

Definition at line 53 of file mavros.h.

◆ gcs_link

mavconn::MAVConnInterface::Ptr mavros::MavRos::gcs_link
private

Definition at line 45 of file mavros.h.

◆ gcs_link_diag

MavlinkDiag mavros::MavRos::gcs_link_diag
private

Definition at line 55 of file mavros.h.

◆ gcs_quiet_mode

bool mavros::MavRos::gcs_quiet_mode
private

Definition at line 46 of file mavros.h.

◆ gps_eph

float mavros::UAS::gps_eph
private

Definition at line 465 of file mavros_uas.h.

◆ gps_epv

float mavros::UAS::gps_epv
private

Definition at line 466 of file mavros_uas.h.

◆ gps_fix

sensor_msgs::NavSatFix::Ptr mavros::UAS::gps_fix
private

Definition at line 464 of file mavros_uas.h.

◆ gps_fix_type

int mavros::UAS::gps_fix_type
private

Definition at line 467 of file mavros_uas.h.

◆ gps_fix_type_strings

const std::array<const std::string, 9> mavros::utils::gps_fix_type_strings
static
Initial value:
{{
"NO_GPS",
"NO_FIX",
"2D_FIX",
"3D_FIX",
"DGPS",
"RTK_FLOAT",
"RTK_FIXED",
"STATIC",
"PPP",
}}

GPS_FIX_TYPE values.

Definition at line 429 of file enum_to_string.cpp.

◆ gps_satellites_visible

int mavros::UAS::gps_satellites_visible
private

Definition at line 468 of file mavros_uas.h.

◆ imu_enu_data

sensor_msgs::Imu::Ptr mavros::UAS::imu_enu_data
private

Definition at line 461 of file mavros_uas.h.

◆ imu_ned_data

sensor_msgs::Imu::Ptr mavros::UAS::imu_ned_data
private

Definition at line 462 of file mavros_uas.h.

◆ is_connected

std::atomic<bool> mavros::MavlinkDiag::is_connected
private

Definition at line 41 of file mavlink_diag.h.

◆ landing_target_type_strings

const std::array<const std::string, 4> mavros::utils::landing_target_type_strings
static
Initial value:
{{
"LIGHT_BEACON",
"RADIO_BEACON",
"VISION_FIDUCIAL",
"VISION_OTHER",
}}

LANDING_TARGET_TYPE values.

Definition at line 746 of file enum_to_string.cpp.

◆ last_drop_count

unsigned int mavros::MavlinkDiag::last_drop_count
private

Definition at line 40 of file mavlink_diag.h.

◆ last_message_received_from_gcs

ros::Time mavros::MavRos::last_message_received_from_gcs
private

Definition at line 47 of file mavros.h.

◆ loaded_plugins

std::vector<plugin::PluginBase::Ptr> mavros::MavRos::loaded_plugins
private

Definition at line 58 of file mavros.h.

◆ mav_autopilot_strings

const std::array<const std::string, 20> mavros::utils::mav_autopilot_strings
static
Initial value:
{{
"Generic autopilot",
"Reserved for future use",
"SLUGS autopilot",
"ArduPilot",
"OpenPilot",
"Generic autopilot only supporting simple waypoints",
"Generic autopilot supporting waypoints and other simple navigation commands",
"Generic autopilot supporting the full mission command set",
"No valid autopilot",
"PPZ UAV",
"UAV Dev Board",
"FlexiPilot",
"PX4 Autopilot",
"SMACCMPilot",
"AutoQuad",
"Armazila",
"Aerob",
"ASLUAV autopilot",
"SmartAP Autopilot",
"AirRails",
}}

MAV_AUTOPILOT values.

Definition at line 108 of file enum_to_string.cpp.

◆ mav_comp_id_strings

const std::unordered_map<typename std::underlying_type<MAV_COMPONENT>::type, const std::string> mavros::utils::mav_comp_id_strings
static

Definition at line 551 of file enum_to_string.cpp.

◆ mav_distance_sensor_strings

const std::array<const std::string, 5> mavros::utils::mav_distance_sensor_strings
static
Initial value:
{{
"LASER",
"ULTRASOUND",
"INFRARED",
"RADAR",
"UNKNOWN",
}}

MAV_DISTANCE_SENSOR values.

Definition at line 723 of file enum_to_string.cpp.

◆ mav_estimator_type_strings

const std::array<const std::string, 9> mavros::utils::mav_estimator_type_strings
static
Initial value:
{{
"UNKNOWN",
"NAIVE",
"VISION",
"VIO",
"GPS",
"GPS_INS",
"MOCAP",
"LIDAR",
"AUTOPILOT",
}}

MAV_ESTIMATOR_TYPE values.

Definition at line 402 of file enum_to_string.cpp.

◆ mav_frame_strings

const std::array<const std::string, 22> mavros::utils::mav_frame_strings
static
Initial value:
{{
"GLOBAL",
"LOCAL_NED",
"MISSION",
"GLOBAL_RELATIVE_ALT",
"LOCAL_ENU",
"GLOBAL_INT",
"GLOBAL_RELATIVE_ALT_INT",
"LOCAL_OFFSET_NED",
"BODY_NED",
"BODY_OFFSET_NED",
"GLOBAL_TERRAIN_ALT",
"GLOBAL_TERRAIN_ALT_INT",
"BODY_FRD",
"RESERVED_13",
"RESERVED_14",
"RESERVED_15",
"RESERVED_16",
"RESERVED_17",
"RESERVED_18",
"RESERVED_19",
"LOCAL_FRD",
"LOCAL_FLU",
}}

MAV_FRAME values.

Definition at line 500 of file enum_to_string.cpp.

◆ mav_mission_result_strings

const std::array<const std::string, 16> mavros::utils::mav_mission_result_strings
static
Initial value:
{{
"mission accepted OK",
"Generic error / not accepting mission commands at all right now.",
"Coordinate frame is not supported.",
"Command is not supported.",
"Mission items exceed storage space.",
"One of the parameters has an invalid value.",
"param1 has an invalid value.",
"param2 has an invalid value.",
"param3 has an invalid value.",
"param4 has an invalid value.",
"x / param5 has an invalid value.",
"y / param6 has an invalid value.",
"z / param7 has an invalid value.",
"Mission item received out of sequence",
"Not accepting any mission commands from this communication partner.",
"Current mission operation cancelled (e.g. mission upload, mission download).",
}}

MAV_MISSION_RESULT values.

Definition at line 466 of file enum_to_string.cpp.

◆ mav_state_strings

const std::array<const std::string, 9> mavros::utils::mav_state_strings
static
Initial value:
{{
"Uninit",
"Boot",
"Calibrating",
"Standby",
"Active",
"Critical",
"Emergency",
"Poweroff",
"Flight_Termination",
}}

MAV_STATE values.

Definition at line 274 of file enum_to_string.cpp.

◆ mav_type_names

const std::array<const std::string, 36> mavros::utils::mav_type_names
static

MAV_TYPE values.

Definition at line 210 of file enum_to_string.cpp.

◆ mav_type_strings

const std::array<const std::string, 36> mavros::utils::mav_type_strings
static

MAV_TYPE values.

Definition at line 156 of file enum_to_string.cpp.

◆ mav_uas

UAS mavros::MavRos::mav_uas
private

UAS object passed to all plugins.

Definition at line 64 of file mavros.h.

◆ mavlink_nh

ros::NodeHandle mavros::MavRos::mavlink_nh
private

Definition at line 43 of file mavros.h.

◆ mavlink_pub

ros::Publisher mavros::MavRos::mavlink_pub
private

Definition at line 50 of file mavros.h.

◆ mavlink_sub

ros::Subscriber mavros::MavRos::mavlink_sub
private

Definition at line 51 of file mavros.h.

◆ mutex

std::recursive_mutex mavros::UAS::mutex
private

Definition at line 448 of file mavros_uas.h.

◆ NED_ENU_Q

const auto mavros::ftf::detail::NED_ENU_Q = quaternion_from_rpy(M_PI, 0.0, M_PI_2)
static

Static quaternion needed for rotating between ENU and NED frames NED to ENU: +PI/2 rotation about Z (Down) followed by a +PI rotation around X (old North/new East) ENU to NED: +PI/2 rotation about Z (Up) followed by a +PI rotation about X (old East/new North)

Definition at line 30 of file ftf_frame_conversions.cpp.

◆ NED_ENU_R

const auto mavros::ftf::detail::NED_ENU_R = NED_ENU_Q.normalized().toRotationMatrix()
static

3-D matrices to fill 6-D rotation matrix applied to change covariance matrices coordinate frames

Definition at line 57 of file ftf_frame_conversions.cpp.

◆ plugin_loader

pluginlib::ClassLoader<plugin::PluginBase> mavros::MavRos::plugin_loader
private

Definition at line 57 of file mavros.h.

◆ plugin_subscriptions

std::unordered_map<mavlink::msgid_t, plugin::PluginBase::Subscriptions> mavros::MavRos::plugin_subscriptions
private

FCU link -> router -> plugin handler.

Definition at line 61 of file mavros.h.

◆ sensor_orientations

const std::unordered_map<typename std::underlying_type<MAV_SENSOR_ORIENTATION>::type, const OrientationPair> mavros::utils::sensor_orientations
static

Definition at line 77 of file enum_sensor_orientation.cpp.

◆ target_component

uint8_t mavros::UAS::target_component
private

Definition at line 455 of file mavros_uas.h.

◆ target_system

uint8_t mavros::UAS::target_system
private

Definition at line 454 of file mavros_uas.h.

◆ tf2_broadcaster

tf2_ros::TransformBroadcaster mavros::UAS::tf2_broadcaster

Definition at line 275 of file mavros_uas.h.

◆ tf2_buffer

tf2_ros::Buffer mavros::UAS::tf2_buffer

Definition at line 273 of file mavros_uas.h.

◆ tf2_listener

tf2_ros::TransformListener mavros::UAS::tf2_listener

Definition at line 274 of file mavros_uas.h.

◆ tf2_static_broadcaster

tf2_ros::StaticTransformBroadcaster mavros::UAS::tf2_static_broadcaster

Definition at line 276 of file mavros_uas.h.

◆ time_offset

std::atomic<uint64_t> mavros::UAS::time_offset
private

Definition at line 470 of file mavros_uas.h.

◆ timesync_mode_strings

const std::array<const std::string, 4> mavros::utils::timesync_mode_strings
static
Initial value:
{{
"NONE",
"MAVLINK",
"ONBOARD",
"PASSTHROUGH",
}}

timesync_mode values

Definition at line 309 of file enum_to_string.cpp.

◆ tsync_mode

timesync_mode mavros::UAS::tsync_mode
private

Definition at line 471 of file mavros_uas.h.

◆ type

std::atomic<uint8_t> mavros::UAS::type
private

Definition at line 450 of file mavros_uas.h.

◆ weak_link

mavconn::MAVConnInterface::WeakPtr mavros::MavlinkDiag::weak_link
private

Definition at line 39 of file mavlink_diag.h.



mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:50