Package master_discovery_fkie :: Module master_discovery :: Class DiscoveredMaster
[frames] | no frames]

Class DiscoveredMaster

source code

object --+
         |
        DiscoveredMaster

The class stores all information about the remote ROS master and the all received heartbeat messages of the remote node. On first contact a theaded connection to remote discoverer will be established to get additional information about the ROS master.

Instance Methods
 
__init__(self, monitoruri, heartbeat_rate=1.0, timestamp=0.0, timestamp_local=0.0, callback_master_state=None)
Initialize method for the DiscoveredMaster class.
source code
 
addHeartbeat(self, timestamp, timestamp_local, rate)
Adds a new heartbeat measurement.
source code
int
removeHeartbeats(self, timestamp)
Removes all hearbeat measurements, which are older as the given timestamp.
source code
 
setOffline(self)
Sets this master to offline and publish the new state to the ROS network.
source code

Inherited from object: __delattr__, __format__, __getattribute__, __hash__, __new__, __reduce__, __reduce_ex__, __repr__, __setattr__, __sizeof__, __str__, __subclasshook__

Properties

Inherited from object: __class__

Method Details

__init__(self, monitoruri, heartbeat_rate=1.0, timestamp=0.0, timestamp_local=0.0, callback_master_state=None)
(Constructor)

source code 

Initialize method for the DiscoveredMaster class.

Parameters:
  • monitoruri (str) - The URI of the remote RPC server, which moniter the ROS master
  • heartbeat_rate (float (Default: 1.)) - The remote rate, which is used to send the heartbeat messages.
  • timestamp (float (Default: c{0})) - The timestamp of the state of the remoter ROS master
  • timestamp_local (float (Default: c{0})) - The timestamp of the state of the remoter ROS master, without the changes maked while a synchronization.
  • callback_master_state (<method>(master_discovery_fkie/MasterState) (Default: None)) - the callback method to publish the changes of the ROS masters
Overrides: object.__init__

addHeartbeat(self, timestamp, timestamp_local, rate)

source code 

Adds a new heartbeat measurement. If it is a new timestamp a ROS message about the change of this ROS master will be published into ROS network.

Parameters:
  • timestamp (float) - The new timestamp of the ROS master state
  • timestamp_local (float (Default: c{0})) - The timestamp of the state of the remoter ROS master, without the changes maked while a synchronization.
  • rate (float) - The remote rate, which is used to send the heartbeat messages.
Returns:
True, on changes

removeHeartbeats(self, timestamp)

source code 

Removes all hearbeat measurements, which are older as the given timestamp.

Parameters:
  • timestamp (float) - heartbeats older this timestamp will be removed.
Returns: int
the count of removed heartbeats