Public Member Functions | |
Subscriptions | get_subscriptions () override |
void | initialize (UAS &uas_) override |
TunnelPlugin () | |
![]() | |
virtual | ~PluginBase () |
Private Member Functions | |
void | mav_callback (const mavlink::mavlink_message_t *, mavlink::common::msg::TUNNEL &mav_tunnel) |
void | ros_callback (const mavros_msgs::Tunnel::ConstPtr &ros_tunnel) |
Static Private Member Functions | |
template<typename From , typename To > | |
static To | copy_tunnel (const From &from) noexcept(false) |
Private Attributes | |
ros::NodeHandle | nh_ |
ros::Publisher | pub_ |
ros::Subscriber | sub_ |
Additional Inherited Members | |
![]() | |
typedef boost::shared_ptr< PluginBase const > | ConstPtr |
typedef mavconn::MAVConnInterface::ReceivedCb | HandlerCb |
typedef std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb > | HandlerInfo |
typedef boost::shared_ptr< PluginBase > | Ptr |
typedef std::vector< HandlerInfo > | Subscriptions |
![]() | |
virtual void | capabilities_cb (UAS::MAV_CAP capabilities) |
virtual void | connection_cb (bool connected) |
void | enable_capabilities_cb () |
void | enable_connection_cb () |
HandlerInfo | make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing)) |
HandlerInfo | make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &)) |
PluginBase () | |
![]() | |
UAS * | m_uas |
Definition at line 10 of file tunnel.cpp.
|
inline |
Definition at line 13 of file tunnel.cpp.
|
inlinestaticprivatenoexcept |
Definition at line 66 of file tunnel.cpp.
|
inlineoverridevirtual |
Implements mavros::plugin::PluginBase.
Definition at line 22 of file tunnel.cpp.
|
inlineoverridevirtual |
Reimplemented from mavros::plugin::PluginBase.
Definition at line 15 of file tunnel.cpp.
|
inlineprivate |
Definition at line 48 of file tunnel.cpp.
|
inlineprivate |
Definition at line 32 of file tunnel.cpp.
|
private |
Definition at line 28 of file tunnel.cpp.
|
private |
Definition at line 30 of file tunnel.cpp.
|
private |
Definition at line 29 of file tunnel.cpp.