31 typedef std::lock_guard<std::recursive_mutex>
lock_guard;
46 using HandlerInfo = std::tuple<mavlink::msgid_t, const char*, size_t, HandlerCb>;
89 auto bfn = std::bind(fn, static_cast<_C*>(
this), std::placeholders::_1, std::placeholders::_2);
90 const auto type_hash_ =
typeid(mavlink::mavlink_message_t).hash_code();
100 template<
class _C,
class _T>
102 auto bfn = std::bind(fn, static_cast<_C*>(
this), std::placeholders::_1, std::placeholders::_2);
103 const auto id = _T::MSG_ID;
104 const auto name = _T::NAME;
105 const auto type_hash_ =
typeid(_T).hash_code();
108 id,
name, type_hash_,
115 obj.deserialize(map);
std::lock_guard< std::recursive_mutex > lock_guard
MAVROS Plugin base class.
std::function< void(const mavlink::mavlink_message_t *message, const Framing framing)> ReceivedCb
std::unique_lock< std::recursive_mutex > unique_lock
std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb > HandlerInfo
Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback.
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
PluginBase()
Plugin constructor Should not do anything before initialize()
void add_connection_change_handler(ConnectionCb cb)
Add connection change handler callback.
virtual Subscriptions get_subscriptions()=0
Return vector of MAVLink message subscriptions (handlers)
virtual void connection_cb(bool connected)
void enable_connection_cb()
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
HandlerInfo make_handler(void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
virtual void initialize(UAS &uas)
Plugin initializer.
mavconn::MAVConnInterface::ReceivedCb HandlerCb
generic message handler callback