Go to the documentation of this file.00001
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #pragma once
00029
00030 #include <map>
00031 #include <diagnostic_updater/diagnostic_updater.h>
00032 #include <mavconn/interface.h>
00033 #include <mavros/mavros_uas.h>
00034
00035 namespace mavplugin {
00036 using mavros::UAS;
00037 typedef std::lock_guard<std::recursive_mutex> lock_guard;
00038 typedef std::unique_lock<std::recursive_mutex> unique_lock;
00039
00043 #define MESSAGE_HANDLER(_message_id, _class_method_ptr) \
00044 { _message_id, boost::bind(_class_method_ptr, this, _1, _2, _3) }
00045
00049 class MavRosPlugin
00050 {
00051 private:
00052 MavRosPlugin(const MavRosPlugin&) = delete;
00053
00054 public:
00055 typedef boost::function<void(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)>
00056 message_handler;
00057 typedef std::map<uint8_t, message_handler> message_map;
00058
00059 typedef boost::shared_ptr<MavRosPlugin> Ptr;
00060 typedef boost::shared_ptr<MavRosPlugin const> ConstPtr;
00061
00062 virtual ~MavRosPlugin() {};
00063
00071 virtual void initialize(UAS &uas,
00072 ros::NodeHandle &nh,
00073 diagnostic_updater::Updater &diag_updater) = 0;
00074
00078 virtual const std::string get_name() const = 0;
00079
00083 virtual const message_map get_rx_handlers() = 0;
00084
00085 protected:
00090 MavRosPlugin() {};
00091 };
00092
00093 };