ros_topology.py
Go to the documentation of this file.
00001 # Copyright 2014 Open Source Robotics Foundation, Inc.
00002 #
00003 # Licensed under the Apache License, Version 2.0 (the "License");
00004 # you may not use this file except in compliance with the License.
00005 # You may obtain a copy of the License at
00006 #
00007 #     http://www.apache.org/licenses/LICENSE-2.0
00008 #
00009 # Unless required by applicable law or agreed to in writing, software
00010 # distributed under the License is distributed on an "AS IS" BASIS,
00011 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00012 # See the License for the specific language governing permissions and
00013 # limitations under the License.
00014 
00015 """
00016 diarc topology data structures for ROS
00017 This renames some things into ROS terminology to be more conveient, and also
00018 adds some attributes we want to track.
00019 
00020 Renaming Looks like this
00021   Vertex = Node
00022   Edge = Topic
00023   Sink = Subscriber
00024   Source = Publisher
00025 """
00026 
00027 from diarc.topology import Topology
00028 from diarc.topology import Vertex
00029 from diarc.topology import Edge
00030 from diarc.topology import Source
00031 from diarc.topology import Sink
00032 from diarc.util import typecheck
00033 
00034 
00035 class RosSystemGraph(Topology):
00036     """ Ros version of Topology """
00037     def __init__(self):
00038         super(RosSystemGraph, self).__init__()
00039 
00040     @property
00041     def nodes(self):
00042         """ dictionary of nodes indexed by name """
00043         return dict([(v.name, v) for v in self.vertices])
00044 
00045     @property
00046     def topics(self):
00047         """ dictionary of topics indexed by name """
00048         return dict(filter(lambda x: None not in x, [(topic.name, topic) for topic in self.edges]))
00049 
00050     def nextFreeNodeIndex(self):
00051         """ returns the next available node index """
00052         return max(self.blocks.keys()) + 1 if len(self.blocks) > 0 else 0
00053 
00054     def nextFreeAltitudes(self):
00055         """ returns a 2-tuple of (posAltitude,negAltitude) of the avaliable altitudes """
00056         altitudes = [band.altitude for band in self.bands.values()] + [0]
00057         return (max(altitudes) + 1, min(altitudes) - 1)
00058 
00059 
00060 class Node(Vertex):
00061     def __init__(self, rsg, name=None):
00062         typecheck(rsg, RosSystemGraph, "rsg")
00063         super(Node, self).__init__(rsg)
00064 
00065         # dumb placement - just get the next free index
00066         self.block.index = rsg.nextFreeNodeIndex()
00067 
00068         self.name = name
00069         self.location = None
00070         self.pid = None
00071         self.num_threads = 0
00072         self.cpu_load_mean = 0
00073         self.cpu_load_std = 0
00074         self.cpu_load_max = 0
00075         self.virt_mem_mean = 0
00076         self.virt_mem_std = 0
00077         self.virt_mem_max = 0
00078         self.real_mem_mean = 0
00079         self.real_mem_std = 0
00080         self.real_mem_max = 0
00081 
00082     @property
00083     def publishers(self):
00084         """ returns publishers """
00085         # NOTE: This must be a property function (instead of just saying
00086         # self.publishers = self.sources in the constructor) because self.sources
00087         # just returns a static list once, and we need this to be dynamically
00088         # queried every time we ask. This is because Vertex.sources and Edge.sources
00089         # are just syntax sugar for functions that are being called.
00090         return self.sources
00091 
00092     @property
00093     def subscribers(self):
00094         """ return subscribers """
00095         return self.sinks
00096 
00097 
00098 class Topic(Edge):
00099     """ ROS version of an Edge """
00100     def __init__(self, rsg, name=None, msgType=None):
00101         typecheck(rsg, RosSystemGraph, "rsg")
00102         super(Topic, self).__init__(rsg)
00103 
00104         # Dumb placement - just get the enxt free altitudes
00105         self.posBand.altitude, self.negBand.altitude = rsg.nextFreeAltitudes()
00106         self.posBand.rank = self.posBand.altitude
00107         self.negBand.rank = self.posBand.altitude
00108 
00109         self.name = name
00110         self.msgType = msgType
00111 
00112         self.hz = 0
00113         self.bw = 0
00114 
00115     @property
00116     def publishers(self):
00117         """ list of publishers """
00118         # NOTE: See note on Node class about why this MUST be a property.
00119         return self.sources
00120 
00121     @property
00122     def subscribers(self):
00123         """ list of subscribers """
00124         # NOTE: See note on Node class about why this MUST be a property.
00125         return self.sinks
00126 
00127 
00128 class Publisher(Source):
00129     """ ROS Version of a source """
00130     def __init__(self, rsg, node, topic):
00131         typecheck(rsg, RosSystemGraph, "rsg")
00132         typecheck(node, Node, "node")
00133         typecheck(topic, Topic, "topic")
00134         super(Publisher, self).__init__(rsg, node, topic)
00135         # Dumb placement
00136         self.snap.order = max(filter(lambda x: isinstance(x, int), [pub.snap.order for pub in node.publishers] + [-1])) + 1
00137 
00138         self.bandwidth = None
00139         self.msgType = None
00140 
00141     @property
00142     def topic(self):
00143         """ topic for this publisher """
00144         # NOTE: See note on Node class about why this MUST be a property.
00145         return self.edge
00146 
00147     @property
00148     def node(self):
00149         """ node for this publisher """
00150         # NOTE: See note on Node class about why this MUST be a property.
00151         return self.vertex
00152 
00153 
00154 class Subscriber(Sink):
00155     """ ROS version of a sink """
00156     def __init__(self, rsg, node, topic):
00157         typecheck(rsg, RosSystemGraph, "rsg")
00158         typecheck(node, Node, "node")
00159         typecheck(topic, Topic, "topic")
00160         super(Subscriber, self).__init__(rsg, node, topic)
00161 
00162         # Dumb placement
00163         self.snap.order = max(filter(lambda x: isinstance(x, int), [sub.snap.order for sub in node.subscribers] + [-1])) + 1
00164 
00165         self.bandwidth = None
00166         self.msgType = None
00167 
00168     @property
00169     def topic(self):
00170         """ topic for this subscriber """
00171         # NOTE: See note on Node class about why this MUST be a property.
00172         return self.edge
00173 
00174     @property
00175     def node(self):
00176         """ node for this subscriber """
00177         # NOTE: See note on Node class about why this MUST be a property.
00178         return self.vertex


rqt_graphprofiler
Author(s): Dan Brooks
autogenerated on Thu Jun 6 2019 20:29:31