MAVROS node implementation. More...
Classes | |
class | mavros::MavlinkDiag |
class | mavros::MavRos |
MAVROS node class. More... | |
class | mavros::UAS |
UAS for plugins. More... | |
Namespaces | |
namespace | mavros |
Defines | |
#define | DEG_TO_RAD (M_PI / 180.0f) |
#define | UAS_DIAG(uasobjptr) ((uasobjptr)->diag_updater) |
helper accessor to diagnostic updater | |
#define | UAS_FCU(uasobjptr) ((uasobjptr)->fcu_link) |
helper accessor to FCU link interface | |
#define | UAS_PACK_CHAN(uasobjptr) |
helper for mavlink_msg_*_pack_chan() | |
#define | UAS_PACK_TGT(uasobjptr) |
helper for pack messages with target fields | |
Typedefs | |
typedef boost::array< double, 9 > | mavros::UAS::Covariance3d |
Type matching rosmsg for covariance 3x3. | |
typedef boost::array< double, 36 > | mavros::UAS::Covariance6d |
Type matching rosmsg for covarince 6x6. | |
typedef Eigen::Map< const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > | mavros::UAS::EigenMapConstCovariance3d |
typedef Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > | mavros::UAS::EigenMapConstCovariance6d |
typedef Eigen::Map < Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > | mavros::UAS::EigenMapCovariance3d |
Eigen::Map for Covariance3d. | |
typedef Eigen::Map < Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > | mavros::UAS::EigenMapCovariance6d |
Eigen::Map for Covariance6d. | |
typedef std::lock_guard < std::recursive_mutex > | mavros::UAS::lock_guard |
typedef std::pair< const std::string, const Eigen::Quaterniond > | OrientationPair |
typedef std::unique_lock < std::recursive_mutex > | mavros::UAS::unique_lock |
Enumerations | |
enum | mavros::UAS::STATIC_TRANSFORM { mavros::UAS::NED_TO_ENU, mavros::UAS::ENU_TO_NED, mavros::UAS::AIRCRAFT_TO_BASELINK, mavros::UAS::BASELINK_TO_AIRCRAFT } |
Orientation transform options when applying rotations to data. More... | |
Functions | |
void | mavros::MavRos::add_plugin (std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist) |
static const Eigen::Affine3d | AIRCRAFT_BASELINK_AFFINE (AIRCRAFT_BASELINK_Q) |
bool | mavros::UAS::cmode_from_str (std::string cmode_str, uint32_t &custom_mode) |
Lookup custom mode for given string. | |
bool | mavros::UAS::get_armed () |
Returns arming status. | |
geometry_msgs::Vector3 | mavros::UAS::get_attitude_angular_velocity () |
Get angular velocity from IMU data. | |
sensor_msgs::Imu::Ptr | mavros::UAS::get_attitude_imu () |
Get IMU data. | |
geometry_msgs::Quaternion | mavros::UAS::get_attitude_orientation () |
Get Attitude orientation quaternion. | |
enum MAV_AUTOPILOT | mavros::UAS::get_autopilot () |
Returns autopilot type. | |
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. | |
sensor_msgs::NavSatFix::Ptr | mavros::UAS::get_gps_fix () |
Retunrs last GPS RAW message. | |
bool | mavros::UAS::get_hil_state () |
Returns HIL status. | |
static const Eigen::Affine3d & | get_static_transform_affine (const UAS::STATIC_TRANSFORM transform) |
uint8_t | mavros::UAS::get_tgt_component () |
Return communication target component. | |
uint8_t | mavros::UAS::get_tgt_system () |
Return communication target system. | |
uint64_t | mavros::UAS::get_time_offset (void) |
enum MAV_TYPE | mavros::UAS::get_type () |
Returns vehicle type. | |
bool | mavros::UAS::is_ardupilotmega () |
Check that FCU is APM. | |
bool | mavros::MavRos::is_blacklisted (std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist) |
bool | mavros::UAS::is_connected () |
Return connection status. | |
bool | mavros::UAS::is_my_target (uint8_t sysid, uint8_t compid) |
Check that sys/comp id's is my target. | |
bool | mavros::UAS::is_my_target (uint8_t sysid) |
Check that system id is my target. | |
bool | mavros::UAS::is_px4 () |
Check that FCU is PX4. | |
void | mavros::MavRos::log_connect_change (bool connected) |
static const OrientationPair | make_orientation (const std::string &name, const double roll, const double pitch, const double yaw) |
void | mavros::MavRos::mavlink_pub_cb (const mavlink_message_t *mmsg, uint8_t sysid, uint8_t compid) |
fcu link -> ros | |
void | mavros::MavRos::mavlink_sub_cb (const mavros_msgs::Mavlink::ConstPtr &rmsg) |
ros -> fcu link | |
mavros::MavlinkDiag::MavlinkDiag (std::string name) | |
mavros::MavRos::MavRos () | |
static const Eigen::Affine3d | NED_ENU_AFFINE (NED_ENU_Q) |
static int | mavros::UAS::orientation_from_str (const std::string &sensor_orientation) |
Retrieve sensor orientation number from alias name. | |
void | mavros::MavRos::plugin_route_cb (const mavlink_message_t *mmsg, uint8_t sysid, uint8_t compid) |
message router | |
static Eigen::Quaterniond | mavros::UAS::quaternion_from_rpy (const Eigen::Vector3d &rpy) |
Convert euler angles to quaternion. | |
static Eigen::Quaterniond | mavros::UAS::quaternion_from_rpy (const double roll, const double pitch, const double yaw) |
Convert euler angles to quaternion. | |
static double | mavros::UAS::quaternion_get_yaw (const Eigen::Quaterniond &q) |
Get Yaw angle from quaternion. | |
static void | mavros::UAS::quaternion_to_mavlink (const Eigen::Quaterniond &q, float qmsg[4]) |
Store Quaternion to MAVLink float[4] format. | |
static Eigen::Vector3d | mavros::UAS::quaternion_to_rpy (const Eigen::Quaterniond &q) |
Convert quaternion to euler angles. | |
static void | mavros::UAS::quaternion_to_rpy (const Eigen::Quaterniond &q, double &roll, double &pitch, double &yaw) |
Convert quaternion to euler angles. | |
void | mavros::MavlinkDiag::run (diagnostic_updater::DiagnosticStatusWrapper &stat) |
static Eigen::Quaterniond | mavros::UAS::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. | |
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::MavRos::spin () |
void | mavros::MavRos::startup_px4_usb_quirk (void) |
start mavlink app on USB | |
void | mavros::UAS::stop (void) |
static std::string | mavros::UAS::str_autopilot (enum MAV_AUTOPILOT ap) |
Represent MAV_AUTOPILOT as string. | |
std::string | mavros::UAS::str_mode_v10 (uint8_t base_mode, uint32_t custom_mode) |
Represent FCU mode as string. | |
static std::string | mavros::UAS::str_sensor_orientation (MAV_SENSOR_ORIENTATION orientation) |
Retrieve alias of the orientation received by MAVLink msg. | |
static std::string | mavros::UAS::str_system_status (enum MAV_STATE st) |
Represent MAV_STATE as string. | |
static std::string | mavros::UAS::str_type (enum MAV_TYPE type) |
Represent MAV_TYPE as string. | |
ros::Time | mavros::UAS::synchronise_stamp (uint32_t time_boot_ms) |
Compute FCU message time from time_boot_ms or time_usec field. | |
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. | |
void | mavros::MavRos::terminate_cb () |
fcu link termination callback | |
static Eigen::Vector3d | mavros::UAS::transform_frame (const Eigen::Vector3d &vec, const Eigen::Quaterniond &q) |
Transform data experessed in one frame to another frame. | |
static Covariance3d | mavros::UAS::transform_frame (const Covariance3d &cov, const Eigen::Quaterniond &q) |
Transform convariance expressed in one frame to another. | |
static Covariance6d | mavros::UAS::transform_frame (const Covariance6d &cov, const Eigen::Quaterniond &q) |
template<class T > | |
static T | mavros::UAS::transform_frame_aircraft_baselink (const T &in) |
Transform data expressed in Aircraft frame to Baselink frame. | |
template<class T > | |
static T | mavros::UAS::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 | mavros::UAS::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 | mavros::UAS::transform_frame_baselink_aircraft (const T &in) |
Transform data expressed in Baselink frame to Aircraft frame. | |
template<class T > | |
static T | mavros::UAS::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 | mavros::UAS::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 | mavros::UAS::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 | mavros::UAS::transform_frame_enu_ned (const T &in) |
Transform data expressed in ENU to NED frame. | |
template<class T > | |
static T | mavros::UAS::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 | mavros::UAS::transform_frame_ned_enu (const T &in) |
Transform data expressed in NED to ENU frame. | |
static double | mavros::UAS::transform_frame_yaw (double yaw) |
static double | mavros::UAS::transform_frame_yaw_enu_ned (double yaw) |
Transform heading from ROS to FCU frame. | |
static double | mavros::UAS::transform_frame_yaw_ned_enu (double yaw) |
Transform heading from FCU to ROS frame. | |
static Eigen::Quaterniond | mavros::UAS::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 | mavros::UAS::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 | mavros::UAS::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 | mavros::UAS::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 | mavros::UAS::transform_orientation_ned_enu (const T &in) |
Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame. | |
static Eigen::Vector3d | mavros::UAS::transform_static_frame (const Eigen::Vector3d &vec, const STATIC_TRANSFORM transform) |
Transform data experessed in one frame to another frame. | |
static Covariance3d | mavros::UAS::transform_static_frame (const Covariance3d &cov, const STATIC_TRANSFORM transform) |
Transform convariance expressed in one frame to another. | |
static Covariance6d | mavros::UAS::transform_static_frame (const Covariance6d &cov, const STATIC_TRANSFORM transform) |
mavros::UAS::UAS () | |
void | mavros::UAS::update_attitude_imu (sensor_msgs::Imu::Ptr &imu) |
Store IMU data. | |
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. | |
void | mavros::UAS::update_heartbeat (uint8_t type_, uint8_t autopilot_, uint8_t base_mode_) |
mavros::MavRos::~MavRos () | |
mavros::UAS::~UAS () | |
Variables | |
static const Eigen::Quaterniond | AIRCRAFT_BASELINK_Q = UAS::quaternion_from_rpy(M_PI, 0.0, 0.0) |
std::atomic< uint8_t > | mavros::UAS::autopilot |
std::atomic< uint8_t > | mavros::UAS::base_mode |
std::atomic< bool > | mavros::UAS::connected |
diagnostic_updater::Updater | mavros::UAS::diag_updater |
Mavros diagnostic updater. | |
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. | |
MavlinkDiag | mavros::MavRos::fcu_link_diag |
mavconn::MAVConnInterface::Ptr | mavros::MavRos::gcs_link |
MavlinkDiag | mavros::MavRos::gcs_link_diag |
float | mavros::UAS::gps_eph |
float | mavros::UAS::gps_epv |
sensor_msgs::NavSatFix::Ptr | mavros::UAS::gps_fix |
int | mavros::UAS::gps_fix_type |
int | mavros::UAS::gps_satellites_visible |
sensor_msgs::Imu::Ptr | mavros::UAS::imu_data |
std::atomic< bool > | mavros::MavlinkDiag::is_connected |
unsigned int | mavros::MavlinkDiag::last_drop_count |
std::vector < mavplugin::MavRosPlugin::Ptr > | mavros::MavRos::loaded_plugins |
UAS | mavros::MavRos::mav_uas |
UAS object passed to all plugins. | |
ros::NodeHandle | mavros::MavRos::mavlink_nh |
ros::Publisher | mavros::MavRos::mavlink_pub |
ros::Subscriber | mavros::MavRos::mavlink_sub |
std::array < mavconn::MAVConnInterface::MessageSig, 256 > | mavros::MavRos::message_route_table |
fcu link interface -> router -> plugin callback | |
std::recursive_mutex | mavros::UAS::mutex |
static const Eigen::Quaterniond | NED_ENU_Q = UAS::quaternion_from_rpy(M_PI, 0.0, M_PI_2) |
pluginlib::ClassLoader < mavplugin::MavRosPlugin > | mavros::MavRos::plugin_loader |
static const std::array< const OrientationPair, 39 > | sensor_orientations |
boost::signals2::signal< void(bool)> | mavros::UAS::sig_connection_changed |
This signal emit when status was changed. | |
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 |
std::atomic< uint64_t > | mavros::UAS::time_offset |
std::atomic< uint8_t > | mavros::UAS::type |
mavconn::MAVConnInterface::WeakPtr | mavros::MavlinkDiag::weak_link |
MAVROS node implementation.
#define DEG_TO_RAD (M_PI / 180.0f) |
Definition at line 19 of file uas_sensor_orientation.cpp.
#define UAS_DIAG | ( | uasobjptr | ) | ((uasobjptr)->diag_updater) |
helper accessor to diagnostic updater
Definition at line 43 of file mavros_uas.h.
#define UAS_FCU | ( | uasobjptr | ) | ((uasobjptr)->fcu_link) |
helper accessor to FCU link interface
Definition at line 37 of file mavros_uas.h.
#define UAS_PACK_CHAN | ( | uasobjptr | ) |
UAS_FCU(uasobjptr)->get_system_id(), \ UAS_FCU(uasobjptr)->get_component_id(), \ UAS_FCU(uasobjptr)->get_channel()
helper for mavlink_msg_*_pack_chan()
Filler for first arguments of *_pack_chan functions.
Definition at line 51 of file mavros_uas.h.
#define UAS_PACK_TGT | ( | uasobjptr | ) |
(uasobjptr)->get_tgt_system(), \ (uasobjptr)->get_tgt_component()
helper for pack messages with target fields
Filler for target_system, target_component fields.
Definition at line 61 of file mavros_uas.h.
typedef boost::array<double, 9> mavros::UAS::Covariance3d |
Type matching rosmsg for covariance 3x3.
Definition at line 86 of file mavros_uas.h.
typedef boost::array<double, 36> mavros::UAS::Covariance6d |
Type matching rosmsg for covarince 6x6.
Definition at line 88 of file mavros_uas.h.
typedef Eigen::Map<const Eigen::Matrix<double, 3, 3, Eigen::RowMajor> > mavros::UAS::EigenMapConstCovariance3d |
Definition at line 92 of file mavros_uas.h.
typedef Eigen::Map<const Eigen::Matrix<double, 6, 6, Eigen::RowMajor> > mavros::UAS::EigenMapConstCovariance6d |
Definition at line 95 of file mavros_uas.h.
typedef Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor> > mavros::UAS::EigenMapCovariance3d |
Eigen::Map for Covariance3d.
Definition at line 91 of file mavros_uas.h.
typedef Eigen::Map<Eigen::Matrix<double, 6, 6, Eigen::RowMajor> > mavros::UAS::EigenMapCovariance6d |
Eigen::Map for Covariance6d.
Definition at line 94 of file mavros_uas.h.
typedef std::lock_guard<std::recursive_mutex> mavros::UAS::lock_guard |
Definition at line 82 of file mavros_uas.h.
typedef std::pair<const std::string, const Eigen::Quaterniond> OrientationPair |
Definition at line 24 of file uas_sensor_orientation.cpp.
typedef std::unique_lock<std::recursive_mutex> mavros::UAS::unique_lock |
Definition at line 83 of file mavros_uas.h.
Orientation transform options when applying rotations to data.
Definition at line 422 of file mavros_uas.h.
void mavros::MavRos::add_plugin | ( | std::string & | pl_name, |
ros::V_string & | blacklist, | ||
ros::V_string & | whitelist | ||
) | [private] |
static const Eigen::Affine3d AIRCRAFT_BASELINK_AFFINE | ( | AIRCRAFT_BASELINK_Q | ) | [static] |
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 214 of file uas_stringify.cpp.
bool mavros::UAS::get_armed | ( | ) | [inline] |
Returns arming status.
Definition at line 162 of file mavros_uas.h.
geometry_msgs::Vector3 UAS::get_attitude_angular_velocity | ( | ) |
sensor_msgs::Imu::Ptr UAS::get_attitude_imu | ( | ) |
Get IMU data.
Definition at line 96 of file uas_data.cpp.
geometry_msgs::Quaternion UAS::get_attitude_orientation | ( | ) |
Get Attitude orientation quaternion.
Definition at line 102 of file uas_data.cpp.
enum MAV_AUTOPILOT mavros::UAS::get_autopilot | ( | ) | [inline] |
Returns autopilot type.
Definition at line 152 of file mavros_uas.h.
uint64_t UAS::get_capabilities | ( | ) |
Definition at line 70 of file uas_data.cpp.
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 145 of file uas_data.cpp.
sensor_msgs::NavSatFix::Ptr UAS::get_gps_fix | ( | ) |
Retunrs last GPS RAW message.
Definition at line 156 of file uas_data.cpp.
bool mavros::UAS::get_hil_state | ( | ) | [inline] |
Returns HIL status.
Definition at line 170 of file mavros_uas.h.
static const Eigen::Affine3d& get_static_transform_affine | ( | const UAS::STATIC_TRANSFORM | transform | ) | [inline, static] |
Definition at line 36 of file uas_frame_conversions.cpp.
uint8_t mavros::UAS::get_tgt_component | ( | ) | [inline] |
Return communication target component.
Definition at line 187 of file mavros_uas.h.
uint8_t mavros::UAS::get_tgt_system | ( | ) | [inline] |
Return communication target system.
Definition at line 180 of file mavros_uas.h.
uint64_t mavros::UAS::get_time_offset | ( | void | ) | [inline] |
Definition at line 244 of file mavros_uas.h.
enum MAV_TYPE mavros::UAS::get_type | ( | ) | [inline] |
Returns vehicle type.
Definition at line 144 of file mavros_uas.h.
bool mavros::UAS::is_ardupilotmega | ( | ) | [inline] |
Check that FCU is APM.
Definition at line 298 of file mavros_uas.h.
bool mavros::MavRos::is_blacklisted | ( | std::string & | pl_name, |
ros::V_string & | blacklist, | ||
ros::V_string & | whitelist | ||
) | [private] |
bool mavros::UAS::is_connected | ( | ) | [inline] |
Return connection status.
Definition at line 125 of file mavros_uas.h.
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 284 of file mavros_uas.h.
bool mavros::UAS::is_my_target | ( | uint8_t | sysid | ) | [inline] |
Check that system id is my target.
Definition at line 291 of file mavros_uas.h.
bool mavros::UAS::is_px4 | ( | ) | [inline] |
Check that FCU is PX4.
Definition at line 305 of file mavros_uas.h.
void mavros::MavRos::log_connect_change | ( | bool | connected | ) | [private] |
static const OrientationPair make_orientation | ( | const std::string & | name, |
const double | roll, | ||
const double | pitch, | ||
const double | yaw | ||
) | [static] |
Definition at line 27 of file uas_sensor_orientation.cpp.
void mavros::MavRos::mavlink_pub_cb | ( | const mavlink_message_t * | mmsg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [private] |
fcu link -> ros
void mavros::MavRos::mavlink_sub_cb | ( | const mavros_msgs::Mavlink::ConstPtr & | rmsg | ) | [private] |
ros -> fcu link
MavlinkDiag::MavlinkDiag | ( | std::string | name | ) | [explicit] |
Definition at line 18 of file mavlink_diag.cpp.
MavRos::MavRos | ( | ) |
Definition at line 29 of file mavros.cpp.
static const Eigen::Affine3d NED_ENU_AFFINE | ( | NED_ENU_Q | ) | [static] |
int UAS::orientation_from_str | ( | const std::string & | sensor_orientation | ) | [static] |
Retrieve sensor orientation number from alias name.
Definition at line 100 of file uas_sensor_orientation.cpp.
void mavros::MavRos::plugin_route_cb | ( | const mavlink_message_t * | mmsg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [private] |
message router
Eigen::Quaterniond UAS::quaternion_from_rpy | ( | const Eigen::Vector3d & | rpy | ) | [static] |
Convert euler angles to quaternion.
Definition at line 25 of file uas_quaternion_utils.cpp.
static Eigen::Quaterniond mavros::UAS::quaternion_from_rpy | ( | const double | roll, |
const double | pitch, | ||
const double | yaw | ||
) | [inline, static] |
Convert euler angles to quaternion.
Definition at line 378 of file mavros_uas.h.
double UAS::quaternion_get_yaw | ( | const Eigen::Quaterniond & | q | ) | [static] |
Get Yaw angle from quaternion.
Replacement function for tf::getYaw()
Definition at line 41 of file uas_quaternion_utils.cpp.
static void mavros::UAS::quaternion_to_mavlink | ( | const Eigen::Quaterniond & | q, |
float | qmsg[4] | ||
) | [inline, static] |
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 412 of file mavros_uas.h.
Eigen::Vector3d UAS::quaternion_to_rpy | ( | const Eigen::Quaterniond & | q | ) | [static] |
Convert quaternion to euler angles.
Reverse operation to quaternion_from_rpy()
Definition at line 35 of file uas_quaternion_utils.cpp.
static void mavros::UAS::quaternion_to_rpy | ( | const Eigen::Quaterniond & | q, |
double & | roll, | ||
double & | pitch, | ||
double & | yaw | ||
) | [inline, static] |
Convert quaternion to euler angles.
Definition at line 392 of file mavros_uas.h.
void MavlinkDiag::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [virtual] |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 24 of file mavlink_diag.cpp.
Eigen::Quaterniond UAS::sensor_orientation_matching | ( | MAV_SENSOR_ORIENTATION | orientation | ) | [static] |
Function to match the received orientation received by MAVLink msg and the rotation of the sensor relative to the FCU.
Definition at line 89 of file uas_sensor_orientation.cpp.
void mavros::MavlinkDiag::set_connection_status | ( | bool | connected | ) | [inline] |
Definition at line 34 of file mavlink_diag.h.
void mavros::MavlinkDiag::set_mavconn | ( | const mavconn::MAVConnInterface::Ptr & | link | ) | [inline] |
Definition at line 30 of file mavlink_diag.h.
void mavros::UAS::set_tgt | ( | uint8_t | sys, |
uint8_t | comp | ||
) | [inline] |
Definition at line 191 of file mavros_uas.h.
void mavros::UAS::set_time_offset | ( | uint64_t | offset_ns | ) | [inline] |
Definition at line 240 of file mavros_uas.h.
void mavros::MavRos::spin | ( | ) |
void mavros::MavRos::startup_px4_usb_quirk | ( | void | ) | [private] |
start mavlink app on USB
void UAS::stop | ( | void | ) |
Stop UAS
Definition at line 40 of file uas_data.cpp.
std::string UAS::str_autopilot | ( | enum MAV_AUTOPILOT | ap | ) | [static] |
Represent MAV_AUTOPILOT as string.
Definition at line 261 of file uas_stringify.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 153 of file uas_stringify.cpp.
std::string UAS::str_sensor_orientation | ( | MAV_SENSOR_ORIENTATION | orientation | ) | [static] |
Retrieve alias of the orientation received by MAVLink msg.
Definition at line 78 of file uas_sensor_orientation.cpp.
std::string UAS::str_system_status | ( | enum MAV_STATE | st | ) | [static] |
Represent MAV_STATE as string.
Definition at line 322 of file uas_stringify.cpp.
std::string UAS::str_type | ( | enum MAV_TYPE | type | ) | [static] |
Represent MAV_TYPE as string.
Definition at line 302 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.
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.
[in] | frame_id | frame for header |
[in] | time_stamp | mavlink message time |
Definition at line 272 of file mavros_uas.h.
void mavros::MavRos::terminate_cb | ( | ) | [private] |
fcu link termination callback
Eigen::Vector3d UAS::transform_frame | ( | const Eigen::Vector3d & | vec, |
const Eigen::Quaterniond & | q | ||
) | [static] |
Transform data experessed in one frame to another frame.
General function. Please use specialized enu-ned and ned-enu variants.
Definition at line 139 of file uas_frame_conversions.cpp.
UAS::Covariance3d UAS::transform_frame | ( | const Covariance3d & | cov, |
const Eigen::Quaterniond & | q | ||
) | [static] |
Transform convariance expressed in one frame to another.
General function. Please use specialized enu-ned and ned-enu variants.
Definition at line 145 of file uas_frame_conversions.cpp.
UAS::Covariance6d UAS::transform_frame | ( | const Covariance6d & | cov, |
const Eigen::Quaterniond & | q | ||
) | [static] |
Definition at line 158 of file uas_frame_conversions.cpp.
static T mavros::UAS::transform_frame_aircraft_baselink | ( | const T & | in | ) | [inline, static] |
Transform data expressed in Aircraft frame to Baselink frame.
Definition at line 531 of file mavros_uas.h.
static T mavros::UAS::transform_frame_aircraft_enu | ( | const T & | in, |
const Eigen::Quaterniond & | q | ||
) | [inline, static] |
Transform data expressed in aircraft frame to ENU frame. Assumes quaternion represents rotation from aircraft frame to ENU frame.
Definition at line 567 of file mavros_uas.h.
static T mavros::UAS::transform_frame_aircraft_ned | ( | const T & | in, |
const Eigen::Quaterniond & | q | ||
) | [inline, static] |
Transform data expressed in aircraft frame to NED frame. Assumes quaternion represents rotation from aircraft frame to NED frame.
Definition at line 549 of file mavros_uas.h.
static T mavros::UAS::transform_frame_baselink_aircraft | ( | const T & | in | ) | [inline, static] |
Transform data expressed in Baselink frame to Aircraft frame.
Definition at line 540 of file mavros_uas.h.
static T mavros::UAS::transform_frame_baselink_enu | ( | const T & | in, |
const Eigen::Quaterniond & | q | ||
) | [inline, static] |
Transform data expressed in baselink to ENU frame. Assumes quaternion represents rotation from basel_link to ENU frame.
Definition at line 594 of file mavros_uas.h.
static T mavros::UAS::transform_frame_enu_aircraft | ( | const T & | in, |
const Eigen::Quaterniond & | q | ||
) | [inline, static] |
Transform data expressed in ENU to aircraft frame. Assumes quaternion represents rotation from ENU to aircraft frame.
Definition at line 576 of file mavros_uas.h.
static T mavros::UAS::transform_frame_enu_baselink | ( | const T & | in, |
const Eigen::Quaterniond & | q | ||
) | [inline, static] |
Transform data expressed in ENU to base_link frame. Assumes quaternion represents rotation from ENU to base_link frame.
Definition at line 585 of file mavros_uas.h.
static T mavros::UAS::transform_frame_enu_ned | ( | const T & | in | ) | [inline, static] |
Transform data expressed in ENU to NED frame.
Definition at line 522 of file mavros_uas.h.
static T mavros::UAS::transform_frame_ned_aircraft | ( | const T & | in, |
const Eigen::Quaterniond & | q | ||
) | [inline, static] |
Transform data expressed in NED to aircraft frame. Assumes quaternion represents rotation from NED to aircraft frame.
Definition at line 558 of file mavros_uas.h.
static T mavros::UAS::transform_frame_ned_enu | ( | const T & | in | ) | [inline, static] |
Transform data expressed in NED to ENU frame.
Definition at line 513 of file mavros_uas.h.
static double mavros::UAS::transform_frame_yaw | ( | double | yaw | ) | [inline, static, private] |
Definition at line 637 of file mavros_uas.h.
static double mavros::UAS::transform_frame_yaw_enu_ned | ( | double | yaw | ) | [inline, static] |
Transform heading from ROS to FCU frame.
Definition at line 601 of file mavros_uas.h.
static double mavros::UAS::transform_frame_yaw_ned_enu | ( | double | yaw | ) | [inline, static] |
Transform heading from FCU to ROS frame.
Definition at line 608 of file mavros_uas.h.
Eigen::Quaterniond UAS::transform_orientation | ( | const Eigen::Quaterniond & | q, |
const STATIC_TRANSFORM | transform | ||
) | [static] |
Transform representation of attitude from 1 frame to another (e.g. transfrom attitude from representing from base_link -> NED to representing base_link -> ENU)
Transform for vector3.
General function. Please use specialized enu-ned and ned-enu variants.
Definition at line 60 of file uas_frame_conversions.cpp.
static T mavros::UAS::transform_orientation_aircraft_baselink | ( | const T & | in | ) | [inline, static] |
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame.
Definition at line 495 of file mavros_uas.h.
static T mavros::UAS::transform_orientation_baselink_aircraft | ( | const T & | in | ) | [inline, static] |
Transform from attitude represented WRT baselink frame to attitude represented WRT body frame.
Definition at line 504 of file mavros_uas.h.
static T mavros::UAS::transform_orientation_enu_ned | ( | const T & | in | ) | [inline, static] |
Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame.
Definition at line 486 of file mavros_uas.h.
static T mavros::UAS::transform_orientation_ned_enu | ( | const T & | in | ) | [inline, static] |
Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame.
Definition at line 477 of file mavros_uas.h.
Eigen::Vector3d UAS::transform_static_frame | ( | const Eigen::Vector3d & | vec, |
const STATIC_TRANSFORM | transform | ||
) | [static] |
Transform data experessed in one frame to another frame.
General function. Please use specialized enu-ned and ned-enu variants.
Definition at line 85 of file uas_frame_conversions.cpp.
UAS::Covariance3d UAS::transform_static_frame | ( | const Covariance3d & | cov, |
const STATIC_TRANSFORM | transform | ||
) | [static] |
Transform convariance expressed in one frame to another.
General function. Please use specialized enu-ned and ned-enu variants.
Definition at line 91 of file uas_frame_conversions.cpp.
UAS::Covariance6d UAS::transform_static_frame | ( | const Covariance6d & | cov, |
const STATIC_TRANSFORM | transform | ||
) | [static] |
Definition at line 125 of file uas_frame_conversions.cpp.
UAS::UAS | ( | ) |
Definition at line 23 of file uas_data.cpp.
void UAS::update_attitude_imu | ( | sensor_msgs::Imu::Ptr & | imu | ) |
Store IMU data.
Definition at line 90 of file uas_data.cpp.
void UAS::update_capabilities | ( | bool | known, |
uint64_t | caps = 0 |
||
) |
Definition at line 81 of file uas_data.cpp.
void UAS::update_connection_status | ( | bool | conn_ | ) |
Update autopilot connection status (every HEARTBEAT/conn_timeout)
Definition at line 53 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 131 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 46 of file uas_data.cpp.
mavros::MavRos::~MavRos | ( | ) | [inline] |
mavros::UAS::~UAS | ( | ) | [inline] |
Definition at line 98 of file mavros_uas.h.
const Eigen::Quaterniond AIRCRAFT_BASELINK_Q = UAS::quaternion_from_rpy(M_PI, 0.0, 0.0) [static] |
Definition at line 31 of file uas_frame_conversions.cpp.
std::atomic<uint8_t> mavros::UAS::autopilot [private] |
Definition at line 616 of file mavros_uas.h.
std::atomic<uint8_t> mavros::UAS::base_mode [private] |
Definition at line 617 of file mavros_uas.h.
std::atomic<bool> mavros::UAS::connected [private] |
Definition at line 622 of file mavros_uas.h.
Mavros diagnostic updater.
Definition at line 113 of file mavros_uas.h.
std::atomic<uint64_t> mavros::UAS::fcu_capabilities [private] |
Definition at line 635 of file mavros_uas.h.
std::atomic<bool> mavros::UAS::fcu_caps_known [private] |
Definition at line 634 of file mavros_uas.h.
MAVLink FCU device conection.
Definition at line 108 of file mavros_uas.h.
MavlinkDiag mavros::MavRos::fcu_link_diag [private] |
MavlinkDiag mavros::MavRos::gcs_link_diag [private] |
float mavros::UAS::gps_eph [private] |
Definition at line 627 of file mavros_uas.h.
float mavros::UAS::gps_epv [private] |
Definition at line 628 of file mavros_uas.h.
Definition at line 626 of file mavros_uas.h.
int mavros::UAS::gps_fix_type [private] |
Definition at line 629 of file mavros_uas.h.
int mavros::UAS::gps_satellites_visible [private] |
Definition at line 630 of file mavros_uas.h.
sensor_msgs::Imu::Ptr mavros::UAS::imu_data [private] |
Definition at line 624 of file mavros_uas.h.
std::atomic<bool> mavros::MavlinkDiag::is_connected [private] |
Definition at line 41 of file mavlink_diag.h.
unsigned int mavros::MavlinkDiag::last_drop_count [private] |
Definition at line 40 of file mavlink_diag.h.
std::vector<mavplugin::MavRosPlugin::Ptr> mavros::MavRos::loaded_plugins [private] |
UAS mavros::MavRos::mav_uas [private] |
ros::NodeHandle mavros::MavRos::mavlink_nh [private] |
ros::Publisher mavros::MavRos::mavlink_pub [private] |
ros::Subscriber mavros::MavRos::mavlink_sub [private] |
std::array<mavconn::MAVConnInterface::MessageSig, 256> mavros::MavRos::message_route_table [private] |
std::recursive_mutex mavros::UAS::mutex [private] |
Definition at line 613 of file mavros_uas.h.
Definition at line 26 of file uas_frame_conversions.cpp.
const std::array<const OrientationPair, 39> sensor_orientations [static] |
Definition at line 36 of file uas_sensor_orientation.cpp.
boost::signals2::signal<void(bool)> mavros::UAS::sig_connection_changed |
This signal emit when status was changed.
bool | connection status |
Definition at line 120 of file mavros_uas.h.
uint8_t mavros::UAS::target_component [private] |
Definition at line 620 of file mavros_uas.h.
uint8_t mavros::UAS::target_system [private] |
Definition at line 619 of file mavros_uas.h.
Definition at line 236 of file mavros_uas.h.
Definition at line 234 of file mavros_uas.h.
Definition at line 235 of file mavros_uas.h.
std::atomic<uint64_t> mavros::UAS::time_offset [private] |
Definition at line 632 of file mavros_uas.h.
std::atomic<uint8_t> mavros::UAS::type [private] |
Definition at line 615 of file mavros_uas.h.
Definition at line 39 of file mavlink_diag.h.