MAVROS node class. More...
#include <mavros.h>
Public Member Functions | |
| MavRos () | |
| void | spin () |
| ~MavRos () | |
Private Member Functions | |
| void | add_plugin (std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist) |
| load plugin More... | |
| void | log_connect_change (bool connected) |
| void | mavlink_pub_cb (const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing) |
| fcu link -> ros More... | |
| void | mavlink_sub_cb (const mavros_msgs::Mavlink::ConstPtr &rmsg) |
| ros -> fcu link More... | |
| void | plugin_route_cb (const mavlink::mavlink_message_t *mmsg, const mavconn::Framing framing) |
| message router More... | |
| void | startup_px4_usb_quirk () |
| start mavlink app on USB More... | |
Private Attributes | |
| ros::Duration | conn_timeout |
| MavlinkDiag | fcu_link_diag |
| diagnostic_updater::Updater | gcs_diag_updater |
| mavconn::MAVConnInterface::Ptr | gcs_link |
| MavlinkDiag | gcs_link_diag |
| bool | gcs_quiet_mode |
| ros::Time | last_message_received_from_gcs |
| std::vector< plugin::PluginBase::Ptr > | loaded_plugins |
| UAS | mav_uas |
| UAS object passed to all plugins. More... | |
| ros::NodeHandle | mavlink_nh |
| ros::Publisher | mavlink_pub |
| ros::Subscriber | mavlink_sub |
| pluginlib::ClassLoader< plugin::PluginBase > | plugin_loader |
| std::unordered_map< mavlink::msgid_t, plugin::PluginBase::Subscriptions > | plugin_subscriptions |
| FCU link -> router -> plugin handler. More... | |