Public Types | Public Member Functions | Public Attributes | Private Attributes | List of all members
mavros::UAS Class Reference

UAS for plugins. More...

#include <mavros_uas.h>

Public Types

using ConnectionCb = std::function< void(bool)>
 
using lock_guard = std::lock_guard< std::recursive_mutex >
 
using MAV_AUTOPILOT = mavlink::common::MAV_AUTOPILOT
 
using MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG
 
using MAV_STATE = mavlink::common::MAV_STATE
 
using MAV_TYPE = mavlink::common::MAV_TYPE
 
using timesync_mode = utils::timesync_mode
 
using unique_lock = std::unique_lock< std::recursive_mutex >
 

Public Member Functions

void add_connection_change_handler (ConnectionCb cb)
 Add connection change handler callback. More...
 
bool cmode_from_str (std::string cmode_str, uint32_t &custom_mode)
 Lookup custom mode for given string. More...
 
template<class T >
double ellipsoid_to_geoid_height (T lla)
 Conversion from height above ellipsoid (WGS-84) to height above geoid (AMSL) More...
 
template<class T >
double geoid_to_ellipsoid_height (T lla)
 Conversion from height above geoid (AMSL) to height above ellipsoid (WGS-84) More...
 
bool get_armed ()
 Returns arming status. More...
 
geometry_msgs::Vector3 get_attitude_angular_velocity_enu ()
 Get angular velocity from IMU data. More...
 
geometry_msgs::Vector3 get_attitude_angular_velocity_ned ()
 Get angular velocity from IMU data. More...
 
sensor_msgs::Imu::Ptr get_attitude_imu_enu ()
 Get IMU data [ENU]. More...
 
sensor_msgs::Imu::Ptr get_attitude_imu_ned ()
 Get IMU data [NED]. More...
 
geometry_msgs::Quaternion get_attitude_orientation_enu ()
 Get Attitude orientation quaternion. More...
 
geometry_msgs::Quaternion get_attitude_orientation_ned ()
 Get Attitude orientation quaternion. More...
 
MAV_AUTOPILOT get_autopilot ()
 Returns autopilot type. More...
 
uint64_t get_capabilities ()
 
void 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 get_gps_fix ()
 Retunrs last GPS RAW message. More...
 
bool get_hil_state ()
 Returns HIL status. More...
 
uint8_t get_tgt_component ()
 Return communication target component. More...
 
uint8_t get_tgt_system ()
 Return communication target system. More...
 
uint64_t get_time_offset (void)
 
timesync_mode get_timesync_mode (void)
 
MAV_TYPE get_type ()
 Returns vehicle type. More...
 
bool is_ardupilotmega ()
 Check that FCU is APM. More...
 
bool is_connected ()
 Return connection status. More...
 
bool is_my_target (uint8_t sysid, uint8_t compid)
 Check that sys/comp id's is my target. More...
 
bool is_my_target (uint8_t sysid)
 Check that system id is my target. More...
 
bool is_px4 ()
 Check that FCU is PX4. More...
 
template<typename _T >
void msg_set_target (_T &msg)
 
void publish_static_transform (const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr)
 Publishes static transform. More...
 
void set_tgt (uint8_t sys, uint8_t comp)
 
void set_time_offset (uint64_t offset_ns)
 
void set_timesync_mode (timesync_mode mode)
 
std::string str_mode_v10 (uint8_t base_mode, uint32_t custom_mode)
 Represent FCU mode as string. More...
 
ros::Time synchronise_stamp (uint32_t time_boot_ms)
 Compute FCU message time from time_boot_ms or time_usec field. More...
 
ros::Time synchronise_stamp (uint64_t time_usec)
 
template<typename T >
std_msgs::Header 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...
 
 UAS ()
 
void update_attitude_imu_enu (sensor_msgs::Imu::Ptr &imu)
 Store IMU data [ENU]. More...
 
void update_attitude_imu_ned (sensor_msgs::Imu::Ptr &imu)
 Store IMU data [NED]. More...
 
void update_capabilities (bool known, uint64_t caps=0)
 
void update_connection_status (bool conn_)
 
void 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 update_heartbeat (uint8_t type_, uint8_t autopilot_, uint8_t base_mode_)
 
 ~UAS ()
 

Public Attributes

diagnostic_updater::Updater diag_updater
 Mavros diagnostic updater. More...
 
std::shared_ptr< GeographicLib::Geoid > egm96_5
 Geoid dataset used to convert between AMSL and WGS-84. More...
 
mavconn::MAVConnInterface::Ptr fcu_link
 MAVLink FCU device conection. More...
 
tf2_ros::TransformBroadcaster tf2_broadcaster
 
tf2_ros::Buffer tf2_buffer
 
tf2_ros::TransformListener tf2_listener
 
tf2_ros::StaticTransformBroadcaster tf2_static_broadcaster
 

Private Attributes

std::atomic< uint8_t > autopilot
 
std::atomic< uint8_t > base_mode
 
std::atomic< bool > connected
 
std::vector< ConnectionCbconnection_cb_vec
 
std::atomic< uint64_t > fcu_capabilities
 
std::atomic< bool > fcu_caps_known
 
float gps_eph
 
float gps_epv
 
sensor_msgs::NavSatFix::Ptr gps_fix
 
int gps_fix_type
 
int gps_satellites_visible
 
sensor_msgs::Imu::Ptr imu_enu_data
 
sensor_msgs::Imu::Ptr imu_ned_data
 
std::recursive_mutex mutex
 
uint8_t target_component
 
uint8_t target_system
 
std::atomic< uint64_t > time_offset
 
timesync_mode tsync_mode
 
std::atomic< uint8_t > type
 

Detailed Description

UAS for plugins.

This class stores some useful data and provides fcu connection, mode stringify utilities.

Currently it stores:

Definition at line 66 of file mavros_uas.h.


The documentation for this class was generated from the following files:


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11