#include <node_status_monitor.hpp>
Classes | |
struct | Entry |
struct | NodeStatus |
struct | NodeStatusChangeEvent |
Public Member Functions | |
NodeID | findNodeWithWorstHealth () const |
template<typename Operator > | |
void | forEachNode (Operator op) const |
void | forgetAllNodes () |
void | forgetNode (NodeID node_id) |
NodeStatus | getNodeStatus (NodeID node_id) const |
bool | isNodeKnown (NodeID node_id) const |
NodeStatusMonitor (INode &node) | |
int | start () |
virtual | ~NodeStatusMonitor () |
Protected Member Functions | |
virtual void | handleNodeStatusChange (const NodeStatusChangeEvent &event) |
virtual void | handleNodeStatusMessage (const ReceivedDataStructure< protocol::NodeStatus > &msg) |
Private Types | |
enum | { TimerPeriodMs100 = 2 } |
typedef MethodBinder< NodeStatusMonitor *, void(NodeStatusMonitor::*)(const ReceivedDataStructure< protocol::NodeStatus > &)> | NodeStatusCallback |
typedef MethodBinder< NodeStatusMonitor *, void(NodeStatusMonitor::*)(const TimerEvent &)> | TimerCallback |
Private Member Functions | |
void | changeNodeStatus (const NodeID node_id, const Entry new_entry_value) |
Entry & | getEntry (NodeID node_id) const |
void | handleNodeStatus (const ReceivedDataStructure< protocol::NodeStatus > &msg) |
void | handleTimerEvent (const TimerEvent &) |
Private Attributes | |
Entry | entries_ [NodeID::Max] |
Subscriber< protocol::NodeStatus, NodeStatusCallback > | sub_ |
TimerEventForwarder< TimerCallback > | timer_ |
This class implements the core functionality of a network monitor. It can be extended by inheritance to add more complex logic, or used directly as is.
Definition at line 22 of file node_status_monitor.hpp.
|
private |
Definition at line 77 of file node_status_monitor.hpp.
|
private |
Definition at line 79 of file node_status_monitor.hpp.
|
private |
Enumerator | |
---|---|
TimerPeriodMs100 |
Definition at line 73 of file node_status_monitor.hpp.
|
inlineexplicit |
Definition at line 184 of file node_status_monitor.hpp.
|
inlinevirtual |
Definition at line 189 of file node_status_monitor.hpp.
|
inlineprivate |
Definition at line 105 of file node_status_monitor.hpp.
|
inline |
This helper method allows to quickly estimate the overall network health. Health of the local node is not considered. Returns an invalid Node ID value if there's no known nodes in the network.
Definition at line 277 of file node_status_monitor.hpp.
|
inline |
Calls the operator for every known node. Operator signature: void (NodeID, NodeStatus)
Definition at line 306 of file node_status_monitor.hpp.
|
inline |
Make all nodes unknown.
Definition at line 226 of file node_status_monitor.hpp.
|
inline |
Make the node unknown.
Definition at line 210 of file node_status_monitor.hpp.
Definition at line 96 of file node_status_monitor.hpp.
|
inline |
Returns status of a given node. Unknown nodes are considered offline. Complexity O(1).
Definition at line 239 of file node_status_monitor.hpp.
|
inlineprivate |
Definition at line 125 of file node_status_monitor.hpp.
|
inlineprotectedvirtual |
Called when a node becomes online, changes status or goes offline. Refer to uavcan.protocol.NodeStatus for the offline timeout value. Overriding is not required.
Reimplemented in uavcan::NodeInfoRetriever.
Definition at line 168 of file node_status_monitor.hpp.
|
inlineprotectedvirtual |
Called for every received message uavcan.protocol.NodeStatus after handleNodeStatusChange(), even if the status code did not change. Overriding is not required.
Reimplemented in uavcan::NodeInfoRetriever.
Definition at line 178 of file node_status_monitor.hpp.
|
inlineprivate |
Definition at line 138 of file node_status_monitor.hpp.
|
inline |
Whether the class has observed this node at least once since initialization. Complexity O(1).
Definition at line 262 of file node_status_monitor.hpp.
|
inline |
Starts the monitor. Destroy the object to stop it. Returns negative error code.
Definition at line 196 of file node_status_monitor.hpp.
|
mutableprivate |
Definition at line 94 of file node_status_monitor.hpp.
|
private |
Definition at line 81 of file node_status_monitor.hpp.
|
private |
Definition at line 83 of file node_status_monitor.hpp.