Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 import roslib
00011 roslib.load_manifest('rocon_orchestra')
00012 import rospy
00013 import re
00014 import concert_msgs.msg as concert_msgs
00015 import concert_msgs.srv as concert_srvs
00016 import pydot
00017
00018
00019
00020
00021
00022
00023 class Implementation:
00024 '''
00025 If a solution implementation is being loaded, this stores the data.
00026 '''
00027 def __init__(self):
00028
00029 self._name = rospy.get_param("~name", "Implementation 42")
00030 self.nodes = rospy.get_param("~nodes", [])
00031 self._topics = rospy.get_param("~topics", [])
00032 self._actions = rospy.get_param("~actions", [])
00033 self._edges = rospy.get_param("~edges", [])
00034 self._dot_graph = rospy.get_param("~dot_graph", "")
00035 self._implementation_publisher = rospy.Publisher("implementation", concert_msgs.Implementation, latch=True)
00036 self.publish()
00037 rospy.loginfo("Orchestration : initialised the implementation server.")
00038
00039 def publish(self):
00040 self._implementation_publisher.publish(self.to_msg())
00041
00042 def to_msg(self):
00043 '''
00044 Might be easier just serving up the whole implementation file and saving that
00045 in a string here.
00046 '''
00047 implementation = concert_msgs.Implementation()
00048 implementation.name = self._name
00049 for node in self.nodes:
00050 implementation.link_graph.nodes.append(concert_msgs.LinkNode(node['id'], node['tuple']))
00051 for topic in self._topics:
00052 implementation.link_graph.topics.append(concert_msgs.LinkConnection(topic['id'], topic['type']))
00053 for action in self._actions:
00054 implementation.link_graph.actions.append(concert_msgs.LinkConnection(action['id'], action['type']))
00055 for edge in self._edges:
00056 implementation.link_graph.edges.append(concert_msgs.LinkEdge(edge['start'], edge['finish'], edge['remap_from'], edge['remap_to']))
00057 implementation.dot_graph = self._dot_graph
00058 return implementation
00059
00060 def rebuild(self, node_client_pairs):
00061 '''
00062 If the node name and client name don't match, rebuild
00063
00064 @param node_client_pairs : list of node id-client name pairs
00065 '''
00066 for pair in node_client_pairs:
00067 node_id = pair[0]
00068 client_name = pair[1]
00069 if node_id != client_name:
00070 for node in self.nodes:
00071 if node['id'] == node_id:
00072 node['id'] = client_name
00073 for topic in self._topics:
00074 if re.search(node_id, topic['id']):
00075 topic['id'] = topic['id'].replace(node_id, client_name)
00076 for action in self._actions:
00077 if re.search(node_id, action['id']) is not None:
00078 action['id'] = action['id'].replace(node_id, client_name)
00079 for edge in self._edges:
00080 if edge['start'] == node_id:
00081 edge['start'] = client_name
00082 if edge['finish'] == node_id:
00083 edge['finish'] = client_name
00084 if re.search(node_id, edge['remap_from']):
00085 edge['remap_from'] = edge['remap_from'].replace(node_id, client_name)
00086 if re.search(node_id, edge['remap_to']):
00087 edge['remap_to'] = edge['remap_to'].replace(node_id, client_name)
00088
00089 def to_dot(self):
00090 graph = pydot.Dot(graph_type='graph')
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100