MAVROS node implementation. More...
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::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::common::MAV_AUTOPILOT |
using | mavros::UAS::MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG |
using | mavros::UAS::MAV_STATE = mavlink::common::MAV_STATE |
using | mavros::UAS::MAV_TYPE = mavlink::common::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::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::ECEF_TO_ENU, mavros::ftf::StaticTF::ENU_TO_ECEF } |
Orientation transform options when applying rotations to data. More... | |
Functions | |
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... | |
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... | |
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... | |
void | mavros::ftf::quaternion_to_mavlink (const Eigen::Quaterniond &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 > | |
T | mavros::ftf::transform_frame_aircraft_baselink (const T &in) |
Transform data expressed in Aircraft frame to Baselink frame. More... | |
template<class T > | |
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 > | |
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 > | |
T | mavros::ftf::transform_frame_baselink_aircraft (const T &in) |
Transform data expressed in Baselink frame to Aircraft frame. More... | |
template<class T > | |
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 > | |
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 > | |
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 > | |
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 > | |
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 > | |
T | mavros::ftf::transform_frame_enu_ned (const T &in) |
Transform data expressed in ENU to NED frame. More... | |
template<class T > | |
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 > | |
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 > | |
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 > | |
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 > | |
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 > | |
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 StaticTF 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) |
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 |
ros::Duration | mavros::MavRos::conn_timeout |
std::atomic< bool > | mavros::UAS::connected |
std::vector< ConnectionCb > | mavros::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::Ptr > | mavros::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< size_t, 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, 5 > | mavros::utils::mav_estimator_type_strings |
MAV_ESTIMATOR_TYPE values. More... | |
static const std::array< const std::string, 20 > | mavros::utils::mav_frame_strings |
MAV_FRAME values. More... | |
static const std::array< const std::string, 15 > | 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, 33 > | mavros::utils::mav_type_names |
MAV_TYPE values. More... | |
static const std::array< const std::string, 33 > | 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::PluginBase > | mavros::MavRos::plugin_loader |
std::unordered_map< mavlink::msgid_t, plugin::PluginBase::Subscriptions > | mavros::MavRos::plugin_subscriptions |
FCU link -> router -> plugin handler. More... | |
static const std::array< const OrientationPair, 42 > | mavros::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 |
MAVROS node implementation.
#define UAS_DIAG | ( | uasobjptr | ) | ((uasobjptr)->diag_updater) |
helper accessor to diagnostic updater
Definition at line 47 of file mavros_uas.h.
#define UAS_FCU | ( | uasobjptr | ) | ((uasobjptr)->fcu_link) |
helper accessor to FCU link interface
Definition at line 41 of file mavros_uas.h.
using mavros::UAS::ConnectionCb = std::function<void(bool)> |
Definition at line 68 of file mavros_uas.h.
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.
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.
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.
using mavros::ftf::EigenMapConstCovariance3d = typedef Eigen::Map<const Eigen::Matrix<double, 3, 3, Eigen::RowMajor> > |
Definition at line 47 of file frame_tf.h.
using mavros::ftf::EigenMapConstCovariance6d = typedef Eigen::Map<const Eigen::Matrix<double, 6, 6, Eigen::RowMajor> > |
Definition at line 51 of file frame_tf.h.
using mavros::ftf::EigenMapConstCovariance9d = typedef Eigen::Map<const Eigen::Matrix<double, 9, 9, Eigen::RowMajor> > |
Definition at line 55 of file frame_tf.h.
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.
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.
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.
using mavros::UAS::lock_guard = std::lock_guard<std::recursive_mutex> |
Definition at line 69 of file mavros_uas.h.
using mavros::ftf::detail::Matrix6d = typedef Eigen::Matrix<double, 6, 6> |
Auxiliar matrices to Covariance transforms.
Definition at line 70 of file ftf_frame_conversions.cpp.
using mavros::ftf::detail::Matrix9d = typedef Eigen::Matrix<double, 9, 9> |
Definition at line 71 of file ftf_frame_conversions.cpp.
using mavros::UAS::MAV_AUTOPILOT = mavlink::common::MAV_AUTOPILOT |
Definition at line 74 of file mavros_uas.h.
using mavros::UAS::MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG |
Definition at line 75 of file mavros_uas.h.
using mavros::UAS::MAV_STATE = mavlink::common::MAV_STATE |
Definition at line 76 of file mavros_uas.h.
using mavros::UAS::MAV_TYPE = mavlink::common::MAV_TYPE |
Definition at line 73 of file mavros_uas.h.
using mavros::utils::OrientationPair = typedef std::pair<const std::string, const Eigen::Quaterniond> |
Definition at line 27 of file enum_sensor_orientation.cpp.
using mavros::UAS::timesync_mode = utils::timesync_mode |
Definition at line 77 of file mavros_uas.h.
using mavros::UAS::unique_lock = std::unique_lock<std::recursive_mutex> |
Definition at line 70 of file mavros_uas.h.
|
strong |
Orientation transform options when applying rotations to data.
Definition at line 60 of file frame_tf.h.
void UAS::add_connection_change_handler | ( | UAS::ConnectionCb | cb | ) |
Add connection change handler callback.
Definition at line 81 of file uas_data.cpp.
|
private |
|
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.
bool UAS::cmode_from_str | ( | std::string | cmode_str, |
uint32_t & | custom_mode | ||
) |
Lookup custom mode for given string.
Complimentary to str_mode_v10()
[in] | cmode_str | string representation of mode |
[out] | custom_mode | decoded value |
Definition at line 250 of file uas_stringify.cpp.
|
inline |
Convert covariance matrix to MAVLink float[n] format.
Definition at line 364 of file frame_tf.h.
|
inline |
Convert upper right triangular of a covariance matrix to MAVLink float[n] format.
Definition at line 373 of file frame_tf.h.
|
inline |
Conversion from height above ellipsoid (WGS-84) to height above geoid (AMSL)
Definition at line 259 of file mavros_uas.h.
|
inline |
Conversion from height above geoid (AMSL) to height above ellipsoid (WGS-84)
Definition at line 246 of file mavros_uas.h.
|
inline |
Returns arming status.
Definition at line 137 of file mavros_uas.h.
geometry_msgs::Vector3 UAS::get_attitude_angular_velocity_enu | ( | ) |
Get angular velocity from IMU data.
Definition at line 165 of file uas_data.cpp.
geometry_msgs::Vector3 UAS::get_attitude_angular_velocity_ned | ( | ) |
Get angular velocity from IMU data.
Definition at line 178 of file uas_data.cpp.
sensor_msgs::Imu::Ptr UAS::get_attitude_imu_enu | ( | ) |
Get IMU data [ENU].
Definition at line 127 of file uas_data.cpp.
sensor_msgs::Imu::Ptr UAS::get_attitude_imu_ned | ( | ) |
Get IMU data [NED].
Definition at line 133 of file uas_data.cpp.
geometry_msgs::Quaternion UAS::get_attitude_orientation_enu | ( | ) |
Get Attitude orientation quaternion.
Definition at line 139 of file uas_data.cpp.
geometry_msgs::Quaternion UAS::get_attitude_orientation_ned | ( | ) |
Get Attitude orientation quaternion.
Definition at line 152 of file uas_data.cpp.
|
inline |
Returns autopilot type.
Definition at line 127 of file mavros_uas.h.
uint64_t UAS::get_capabilities | ( | ) |
Definition at line 95 of file uas_data.cpp.
Returns EPH, EPV, Fix type and satellites visible.
Definition at line 208 of file uas_data.cpp.
sensor_msgs::NavSatFix::Ptr UAS::get_gps_fix | ( | ) |
Retunrs last GPS RAW message.
Definition at line 219 of file uas_data.cpp.
|
inline |
Returns HIL status.
Definition at line 145 of file mavros_uas.h.
|
inline |
Return communication target component.
Definition at line 162 of file mavros_uas.h.
|
inline |
Return communication target system.
Definition at line 155 of file mavros_uas.h.
|
inline |
Definition at line 289 of file mavros_uas.h.
|
inline |
Definition at line 297 of file mavros_uas.h.
|
inline |
Returns vehicle type.
Definition at line 119 of file mavros_uas.h.
|
inline |
Check that FCU is APM.
Definition at line 360 of file mavros_uas.h.
|
inline |
Return connection status.
Definition at line 95 of file mavros_uas.h.
|
inline |
Check that sys/comp id's is my target.
Definition at line 346 of file mavros_uas.h.
|
inline |
Check that system id is my target.
Definition at line 353 of file mavros_uas.h.
|
inline |
Check that FCU is PX4.
Definition at line 367 of file mavros_uas.h.
|
private |
Definition at line 369 of file mavros.cpp.
|
static |
Definition at line 30 of file enum_sensor_orientation.cpp.
|
private |
fcu link -> ros
Definition at line 207 of file mavros.cpp.
|
private |
ros -> fcu link
Definition at line 219 of file mavros.cpp.
|
inline |
Convert Mavlink float[4] quaternion to Eigen.
Definition at line 355 of file frame_tf.h.
|
inline |
Convert MAVLink float[n] format (upper right triangular of a covariance matrix) to Eigen::MatrixXd<n,n> full covariance matrix.
Definition at line 394 of file frame_tf.h.
|
explicit |
Definition at line 18 of file mavlink_diag.cpp.
MavRos::MavRos | ( | ) |
Definition at line 31 of file mavros.cpp.
|
inline |
Helper template to set target id's of message.
Definition at line 338 of file mavros_uas.h.
|
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.
|
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.
|
static |
|
private |
message router
Definition at line 229 of file mavros.cpp.
void UAS::publish_static_transform | ( | const std::string & | frame_id, |
const std::string & | child_id, | ||
const Eigen::Affine3d & | tr | ||
) |
Publishes static transform.
frame_id | parent frame for transform |
child_id | child frame for transform |
tr | transform |
Definition at line 228 of file uas_data.cpp.
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.
|
inline |
Convert euler angles to quaternion.
Definition at line 309 of file frame_tf.h.
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.
|
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 344 of file frame_tf.h.
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.
|
inline |
Convert quaternion to euler angles.
Definition at line 323 of file frame_tf.h.
|
virtual |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 24 of file mavlink_diag.cpp.
Eigen::Quaterniond mavros::utils::sensor_orientation_matching | ( | MAV_SENSOR_ORIENTATION | orientation | ) |
Definition at line 134 of file enum_sensor_orientation.cpp.
|
inline |
Definition at line 34 of file mavlink_diag.h.
|
inline |
Definition at line 30 of file mavlink_diag.h.
|
inline |
Definition at line 166 of file mavros_uas.h.
|
inline |
Definition at line 285 of file mavros_uas.h.
|
inline |
Definition at line 293 of file mavros_uas.h.
void MavRos::spin | ( | ) |
Definition at line 186 of file mavros.cpp.
|
private |
start mavlink app on USB
Definition at line 357 of file mavros.cpp.
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:
[in] | base_mode | base mode |
[in] | custom_mode | custom mode data |
Definition at line 185 of file uas_stringify.cpp.
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
Definition at line 32 of file uas_timesync.cpp.
ros::Time UAS::synchronise_stamp | ( | uint64_t | time_usec | ) |
Definition at line 44 of file uas_timesync.cpp.
|
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.
[in] | frame_id | frame for header |
[in] | time_stamp | mavlink message time |
Definition at line 325 of file mavros_uas.h.
|
inline |
Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.
Definition at line 423 of file frame_tf.h.
|
inline |
Helper to convert common ROS geometry_msgs::Vector3 to Eigen::Vector3d.
Definition at line 427 of file frame_tf.h.
|
inline |
Helper to convert common ROS geometry_msgs::Quaternion to Eigen::Quaterniond.
Definition at line 431 of file frame_tf.h.
std::string mavros::utils::to_name | ( | MAV_TYPE | e | ) |
Definition at line 243 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_SENSOR_ORIENTATION | orientation | ) |
Definition at line 123 of file enum_sensor_orientation.cpp.
std::string mavros::utils::to_string | ( | MAV_AUTOPILOT | e | ) |
Definition at line 131 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_TYPE | e | ) |
Definition at line 192 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_STATE | e | ) |
Definition at line 280 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | ADSB_ALTITUDE_TYPE | e | ) |
Definition at line 343 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | ADSB_EMITTER_TYPE | e | ) |
Definition at line 381 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_ESTIMATOR_TYPE | e | ) |
Definition at line 404 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | GPS_FIX_TYPE | e | ) |
Definition at line 431 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_MISSION_RESULT | e | ) |
Definition at line 474 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_FRAME | e | ) |
Definition at line 512 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_COMPONENT | e | ) |
Definition at line 582 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | MAV_DISTANCE_SENSOR | e | ) |
Definition at line 632 of file enum_to_string.cpp.
std::string mavros::utils::to_string | ( | LANDING_TARGET_TYPE | e | ) |
Definition at line 654 of file enum_to_string.cpp.
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 229 of file ftf_frame_conversions.cpp.
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 235 of file ftf_frame_conversions.cpp.
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 245 of file ftf_frame_conversions.cpp.
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 260 of file ftf_frame_conversions.cpp.
|
inline |
Transform data expressed in Aircraft frame to Baselink frame.
Definition at line 205 of file frame_tf.h.
|
inline |
Transform data expressed in aircraft frame to ENU frame. Assumes quaternion represents rotation from aircraft frame to ENU frame.
Definition at line 265 of file frame_tf.h.
|
inline |
Transform data expressed in aircraft frame to NED frame. Assumes quaternion represents rotation from aircraft frame to NED frame.
Definition at line 247 of file frame_tf.h.
|
inline |
Transform data expressed in Baselink frame to Aircraft frame.
Definition at line 214 of file frame_tf.h.
|
inline |
Transform data expressed in baselink to ENU frame. Assumes quaternion represents rotation from basel_link to ENU frame.
Definition at line 292 of file frame_tf.h.
|
inline |
Transform data expressed in ECEF frame to ENU frame.
in | local ECEF coordinates [m] |
map_origin | geodetic origin [lla] |
Definition at line 226 of file frame_tf.h.
|
inline |
Transform data expressed in ENU to aircraft frame. Assumes quaternion represents rotation from ENU to aircraft frame.
Definition at line 274 of file frame_tf.h.
|
inline |
Transform data expressed in ENU to base_link frame. Assumes quaternion represents rotation from ENU to base_link frame.
Definition at line 283 of file frame_tf.h.
|
inline |
Transform data expressed in ENU frame to ECEF frame.
in | local ENU coordinates [m] |
map_origin | geodetic origin [lla] |
Definition at line 238 of file frame_tf.h.
|
inline |
Transform data expressed in ENU to NED frame.
Definition at line 196 of file frame_tf.h.
|
inline |
Transform data expressed in NED to aircraft frame. Assumes quaternion represents rotation from NED to aircraft frame.
Definition at line 256 of file frame_tf.h.
|
inline |
Transform data expressed in NED to ENU frame.
Definition at line 187 of file frame_tf.h.
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 74 of file ftf_frame_conversions.cpp.
|
inline |
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame.
Definition at line 170 of file frame_tf.h.
|
inline |
Transform from attitude represented WRT baselink frame to attitude represented WRT body frame.
Definition at line 179 of file frame_tf.h.
|
inline |
Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame.
Definition at line 161 of file frame_tf.h.
|
inline |
Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame.
Definition at line 152 of file frame_tf.h.
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 91 of file ftf_frame_conversions.cpp.
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 104 of file ftf_frame_conversions.cpp.
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 124 of file ftf_frame_conversions.cpp.
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 155 of file ftf_frame_conversions.cpp.
Eigen::Vector3d mavros::ftf::detail::transform_static_frame | ( | const Eigen::Vector3d & | vec, |
const Eigen::Vector3d & | map_origin, | ||
const StaticTF | 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 188 of file ftf_frame_conversions.cpp.
UAS::UAS | ( | ) |
Definition at line 24 of file uas_data.cpp.
void UAS::update_attitude_imu_enu | ( | sensor_msgs::Imu::Ptr & | imu | ) |
Store IMU data [ENU].
Definition at line 115 of file uas_data.cpp.
void UAS::update_attitude_imu_ned | ( | sensor_msgs::Imu::Ptr & | imu | ) |
Store IMU data [NED].
Definition at line 121 of file uas_data.cpp.
void UAS::update_capabilities | ( | bool | known, |
uint64_t | caps = 0 |
||
) |
Definition at line 106 of file uas_data.cpp.
void UAS::update_connection_status | ( | bool | conn_ | ) |
Update autopilot connection status (every HEARTBEAT/conn_timeout)
Definition at line 70 of file uas_data.cpp.
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 194 of file uas_data.cpp.
void UAS::update_heartbeat | ( | uint8_t | type_, |
uint8_t | autopilot_, | ||
uint8_t | base_mode_ | ||
) |
Update autopilot type on every HEARTBEAT
Definition at line 63 of file uas_data.cpp.
|
inline |
Definition at line 80 of file mavros_uas.h.
|
static |
ADSB_ALTITUDE_TYPE values.
Definition at line 338 of file enum_to_string.cpp.
|
static |
ADSB_EMITTER_TYPE values.
Definition at line 358 of file enum_to_string.cpp.
|
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 36 of file ftf_frame_conversions.cpp.
|
static |
Definition at line 57 of file ftf_frame_conversions.cpp.
|
private |
Definition at line 401 of file mavros_uas.h.
|
private |
Definition at line 402 of file mavros_uas.h.
|
private |
|
private |
Definition at line 407 of file mavros_uas.h.
|
private |
Definition at line 408 of file mavros_uas.h.
diagnostic_updater::Updater mavros::UAS::diag_updater |
Mavros diagnostic updater.
Definition at line 90 of file mavros_uas.h.
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 239 of file mavros_uas.h.
|
private |
Definition at line 423 of file mavros_uas.h.
|
private |
Definition at line 422 of file mavros_uas.h.
mavconn::MAVConnInterface::Ptr mavros::UAS::fcu_link |
MAVLink FCU device conection.
Definition at line 80 of file mavros_uas.h.
|
private |
|
private |
|
private |
Definition at line 414 of file mavros_uas.h.
|
private |
Definition at line 415 of file mavros_uas.h.
|
private |
Definition at line 413 of file mavros_uas.h.
|
private |
Definition at line 416 of file mavros_uas.h.
|
static |
GPS_FIX_TYPE values.
Definition at line 419 of file enum_to_string.cpp.
|
private |
Definition at line 417 of file mavros_uas.h.
|
private |
Definition at line 410 of file mavros_uas.h.
|
private |
Definition at line 411 of file mavros_uas.h.
|
private |
Definition at line 41 of file mavlink_diag.h.
|
static |
LANDING_TARGET_TYPE values.
Definition at line 647 of file enum_to_string.cpp.
|
private |
Definition at line 40 of file mavlink_diag.h.
|
private |
|
private |
|
static |
MAV_AUTOPILOT values.
Definition at line 108 of file enum_to_string.cpp.
|
static |
Definition at line 538 of file enum_to_string.cpp.
|
static |
MAV_DISTANCE_SENSOR values.
Definition at line 624 of file enum_to_string.cpp.
|
static |
MAV_ESTIMATOR_TYPE values.
Definition at line 396 of file enum_to_string.cpp.
|
static |
MAV_FRAME values.
Definition at line 489 of file enum_to_string.cpp.
|
static |
MAV_MISSION_RESULT values.
Definition at line 456 of file enum_to_string.cpp.
|
static |
MAV_STATE values.
Definition at line 268 of file enum_to_string.cpp.
|
static |
MAV_TYPE values.
Definition at line 207 of file enum_to_string.cpp.
|
static |
MAV_TYPE values.
Definition at line 156 of file enum_to_string.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |
Definition at line 398 of file mavros_uas.h.
|
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 29 of file ftf_frame_conversions.cpp.
|
static |
3-D matrices to fill 6-D rotation matrix applied to change covariance matrices coordinate frames
Definition at line 56 of file ftf_frame_conversions.cpp.
|
private |
|
private |
|
static |
Definition at line 76 of file enum_sensor_orientation.cpp.
|
private |
Definition at line 405 of file mavros_uas.h.
|
private |
Definition at line 404 of file mavros_uas.h.
tf2_ros::TransformBroadcaster mavros::UAS::tf2_broadcaster |
Definition at line 271 of file mavros_uas.h.
tf2_ros::Buffer mavros::UAS::tf2_buffer |
Definition at line 269 of file mavros_uas.h.
tf2_ros::TransformListener mavros::UAS::tf2_listener |
Definition at line 270 of file mavros_uas.h.
tf2_ros::StaticTransformBroadcaster mavros::UAS::tf2_static_broadcaster |
Definition at line 272 of file mavros_uas.h.
|
private |
Definition at line 419 of file mavros_uas.h.
|
static |
timesync_mode values
Definition at line 303 of file enum_to_string.cpp.
|
private |
Definition at line 420 of file mavros_uas.h.
|
private |
Definition at line 400 of file mavros_uas.h.
|
private |
Definition at line 39 of file mavlink_diag.h.