Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Private Member Functions | Private Attributes
mavros::UAS Class Reference

UAS for plugins. More...

#include <mavros_uas.h>

List of all members.

Public Types

typedef boost::array< double, 9 > Covariance3d
 Type matching rosmsg for covariance 3x3.
typedef boost::array< double, 36 > Covariance6d
 Type matching rosmsg for covarince 6x6.
typedef Eigen::Map< const
Eigen::Matrix< double,
3, 3, Eigen::RowMajor > > 
EigenMapConstCovariance3d
typedef Eigen::Map< const
Eigen::Matrix< double,
6, 6, Eigen::RowMajor > > 
EigenMapConstCovariance6d
typedef Eigen::Map
< Eigen::Matrix< double,
3, 3, Eigen::RowMajor > > 
EigenMapCovariance3d
 Eigen::Map for Covariance3d.
typedef Eigen::Map
< Eigen::Matrix< double,
6, 6, Eigen::RowMajor > > 
EigenMapCovariance6d
 Eigen::Map for Covariance6d.
typedef std::lock_guard
< std::recursive_mutex > 
lock_guard
enum  STATIC_TRANSFORM { NED_TO_ENU, ENU_TO_NED, AIRCRAFT_TO_BASELINK, BASELINK_TO_AIRCRAFT }
 Orientation transform options when applying rotations to data. More...
typedef std::unique_lock
< std::recursive_mutex > 
unique_lock

Public Member Functions

bool cmode_from_str (std::string cmode_str, uint32_t &custom_mode)
 Lookup custom mode for given string.
bool get_armed ()
 Returns arming status.
geometry_msgs::Vector3 get_attitude_angular_velocity ()
 Get angular velocity from IMU data.
sensor_msgs::Imu::Ptr get_attitude_imu ()
 Get IMU data.
geometry_msgs::Quaternion get_attitude_orientation ()
 Get Attitude orientation quaternion.
enum MAV_AUTOPILOT get_autopilot ()
 Returns autopilot type.
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.
sensor_msgs::NavSatFix::Ptr get_gps_fix ()
 Retunrs last GPS RAW message.
bool get_hil_state ()
 Returns HIL status.
uint8_t get_tgt_component ()
 Return communication target component.
uint8_t get_tgt_system ()
 Return communication target system.
uint64_t get_time_offset (void)
enum MAV_TYPE get_type ()
 Returns vehicle type.
bool is_ardupilotmega ()
 Check that FCU is APM.
bool is_connected ()
 Return connection status.
bool is_my_target (uint8_t sysid, uint8_t compid)
 Check that sys/comp id's is my target.
bool is_my_target (uint8_t sysid)
 Check that system id is my target.
bool is_px4 ()
 Check that FCU is PX4.
void set_tgt (uint8_t sys, uint8_t comp)
void set_time_offset (uint64_t offset_ns)
void stop (void)
std::string str_mode_v10 (uint8_t base_mode, uint32_t custom_mode)
 Represent FCU mode as string.
ros::Time synchronise_stamp (uint32_t time_boot_ms)
 Compute FCU message time from time_boot_ms or time_usec field.
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.
 UAS ()
void update_attitude_imu (sensor_msgs::Imu::Ptr &imu)
 Store IMU data.
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.
void update_heartbeat (uint8_t type_, uint8_t autopilot_, uint8_t base_mode_)
 ~UAS ()

Static Public Member Functions

static int orientation_from_str (const std::string &sensor_orientation)
 Retrieve sensor orientation number from alias name.
static Eigen::Quaterniond quaternion_from_rpy (const Eigen::Vector3d &rpy)
 Convert euler angles to quaternion.
static Eigen::Quaterniond quaternion_from_rpy (const double roll, const double pitch, const double yaw)
 Convert euler angles to quaternion.
static double quaternion_get_yaw (const Eigen::Quaterniond &q)
 Get Yaw angle from quaternion.
static void quaternion_to_mavlink (const Eigen::Quaterniond &q, float qmsg[4])
 Store Quaternion to MAVLink float[4] format.
static Eigen::Vector3d quaternion_to_rpy (const Eigen::Quaterniond &q)
 Convert quaternion to euler angles.
static void quaternion_to_rpy (const Eigen::Quaterniond &q, double &roll, double &pitch, double &yaw)
 Convert quaternion to euler angles.
static Eigen::Quaterniond sensor_orientation_matching (MAV_SENSOR_ORIENTATION orientation)
 Function to match the received orientation received by MAVLink msg and the rotation of the sensor relative to the FCU.
static std::string str_autopilot (enum MAV_AUTOPILOT ap)
 Represent MAV_AUTOPILOT as string.
static std::string str_sensor_orientation (MAV_SENSOR_ORIENTATION orientation)
 Retrieve alias of the orientation received by MAVLink msg.
static std::string str_system_status (enum MAV_STATE st)
 Represent MAV_STATE as string.
static std::string str_type (enum MAV_TYPE type)
 Represent MAV_TYPE as string.
static Eigen::Vector3d transform_frame (const Eigen::Vector3d &vec, const Eigen::Quaterniond &q)
 Transform data experessed in one frame to another frame.
static Covariance3d transform_frame (const Covariance3d &cov, const Eigen::Quaterniond &q)
 Transform convariance expressed in one frame to another.
static Covariance6d transform_frame (const Covariance6d &cov, const Eigen::Quaterniond &q)
template<class T >
static T transform_frame_aircraft_baselink (const T &in)
 Transform data expressed in Aircraft frame to Baselink frame.
template<class T >
static T 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.
template<class T >
static T 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.
template<class T >
static T transform_frame_baselink_aircraft (const T &in)
 Transform data expressed in Baselink frame to Aircraft frame.
template<class T >
static T 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.
template<class T >
static T 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.
template<class T >
static T 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.
template<class T >
static T transform_frame_enu_ned (const T &in)
 Transform data expressed in ENU to NED frame.
template<class T >
static T 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.
template<class T >
static T transform_frame_ned_enu (const T &in)
 Transform data expressed in NED to ENU frame.
static double transform_frame_yaw_enu_ned (double yaw)
 Transform heading from ROS to FCU frame.
static double transform_frame_yaw_ned_enu (double yaw)
 Transform heading from FCU to ROS frame.
static Eigen::Quaterniond transform_orientation (const Eigen::Quaterniond &q, const STATIC_TRANSFORM 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)
template<class T >
static T transform_orientation_aircraft_baselink (const T &in)
 Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame.
template<class T >
static T transform_orientation_baselink_aircraft (const T &in)
 Transform from attitude represented WRT baselink frame to attitude represented WRT body frame.
template<class T >
static T transform_orientation_enu_ned (const T &in)
 Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame.
template<class T >
static T transform_orientation_ned_enu (const T &in)
 Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame.
static Eigen::Vector3d transform_static_frame (const Eigen::Vector3d &vec, const STATIC_TRANSFORM transform)
 Transform data experessed in one frame to another frame.
static Covariance3d transform_static_frame (const Covariance3d &cov, const STATIC_TRANSFORM transform)
 Transform convariance expressed in one frame to another.
static Covariance6d transform_static_frame (const Covariance6d &cov, const STATIC_TRANSFORM transform)

Public Attributes

diagnostic_updater::Updater diag_updater
 Mavros diagnostic updater.
mavconn::MAVConnInterface::Ptr fcu_link
 MAVLink FCU device conection.
boost::signals2::signal< void(bool)> sig_connection_changed
 This signal emit when status was changed.
tf2_ros::TransformBroadcaster tf2_broadcaster
tf2_ros::Buffer tf2_buffer
tf2_ros::TransformListener tf2_listener

Static Private Member Functions

static double transform_frame_yaw (double yaw)

Private Attributes

std::atomic< uint8_t > autopilot
std::atomic< uint8_t > base_mode
std::atomic< bool > connected
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_data
std::recursive_mutex mutex
uint8_t target_component
uint8_t target_system
std::atomic< uint64_t > time_offset
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 80 of file mavros_uas.h.


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


mavros
Author(s): Vladimir Ermakov
autogenerated on Thu Feb 9 2017 04:00:18