Class Endpoint
Defined in File mavros_router.hpp
Inheritance Relationships
Base Type
public std::enable_shared_from_this< Endpoint >
Derived Types
public mavros::router::MAVConnEndpoint
(Class MAVConnEndpoint)public mavros::router::ROSEndpoint
(Class ROSEndpoint)
Class Documentation
-
class Endpoint : public std::enable_shared_from_this<Endpoint>
Endpoint base class
Represents one network connection to the Router
One endpoint could map to several remote devices, e.g. mesh radio for swarm.
Subclassed by mavros::router::MAVConnEndpoint, mavros::router::ROSEndpoint
Public Functions
-
inline Endpoint()
-
virtual bool is_open() = 0
-
virtual std::pair<bool, std::string> open() = 0
-
virtual void close() = 0
-
virtual void send_message(const mavlink_message_t *msg, const Framing framing = Framing::ok, id_t src_id = 0) = 0
-
virtual void recv_message(const mavlink_message_t *msg, const Framing framing = Framing::ok)
-
virtual std::string diag_name()
-
virtual void diag_run(diagnostic_updater::DiagnosticStatusWrapper &stat) = 0
-
inline Endpoint()