mavros.h
Go to the documentation of this file.
00001 
00010 /*
00011  * Copyright 2014,2015 Vladimir Ermakov.
00012  *
00013  * This file is part of the mavros package and subject to the license terms
00014  * in the top-level LICENSE file of the mavros repository.
00015  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
00016  */
00017 
00018 #pragma once
00019 
00020 #include <array>
00021 #include <ros/ros.h>
00022 #include <pluginlib/class_loader.h>
00023 #include <mavconn/interface.h>
00024 #include <mavros/mavros_plugin.h>
00025 #include <mavros/mavlink_diag.h>
00026 #include <mavros/utils.h>
00027 
00028 namespace mavros {
00034 class MavRos
00035 {
00036 public:
00037         MavRos();
00038         ~MavRos() {};
00039 
00040         void spin();
00041 
00042 private:
00043         ros::NodeHandle mavlink_nh;
00044         // fcu_link stored in mav_uas
00045         mavconn::MAVConnInterface::Ptr gcs_link;
00046 
00047         ros::Publisher mavlink_pub;
00048         ros::Subscriber mavlink_sub;
00049 
00050         MavlinkDiag fcu_link_diag;
00051         MavlinkDiag gcs_link_diag;
00052 
00053         pluginlib::ClassLoader<mavplugin::MavRosPlugin> plugin_loader;
00054         std::vector<mavplugin::MavRosPlugin::Ptr> loaded_plugins;
00056         std::array<mavconn::MAVConnInterface::MessageSig, 256> message_route_table;
00058         UAS mav_uas;
00059 
00061         void mavlink_pub_cb(const mavlink_message_t *mmsg, uint8_t sysid, uint8_t compid);
00063         void mavlink_sub_cb(const mavros_msgs::Mavlink::ConstPtr &rmsg);
00064 
00066         void plugin_route_cb(const mavlink_message_t *mmsg, uint8_t sysid, uint8_t compid);
00067 
00068         bool is_blacklisted(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist);
00069         void add_plugin(std::string &pl_name, ros::V_string &blacklist, ros::V_string &whitelist);
00070 
00072         void terminate_cb();
00074         void startup_px4_usb_quirk(void);
00075         void log_connect_change(bool connected);
00076 };
00077 };      // namespace mavros
00078 


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