conductor_graph_to_string.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_concert/license/LICENSE
00005 ###############################################################################
00006 
00007 import rospy
00008 
00009 import std_msgs.msg as std_msgs
00010 from qt_dotgraph.pydotfactory import PydotFactory
00011 
00012 from .dotcode import ConductorGraphDotcodeGenerator
00013 from .conductor_graph_info import ConductorGraphInfo
00014 
00015 
00016 class ConductorGraphDotcodeToString():
00017 
00018     def __init__(self, clusters=False):
00019 
00020         self._clusters = clusters
00021         self._dotcode_factory = PydotFactory()
00022         self._dotcode_generator = ConductorGraphDotcodeGenerator()
00023         self._pub_string = None
00024 
00025         self._graph = ConductorGraphInfo(change_callback=self._update_conductor_graph, periodic_callback=self._periodic_callback)
00026 
00027         while not self._graph.is_conductor and not rospy.is_shutdown():
00028             #self.loginfo("waits for conductor to be ready.")
00029             rospy.rostime.wallsleep(1)
00030 
00031         self._pub_string = rospy.Publisher(self._graph.namespace + '/graph_string', std_msgs.String, queue_size=2)
00032 
00033     def _update_conductor_graph(self):
00034         current_dotcode = self._dotcode_generator.generate_dotcode(conductor_graph_instance=self._graph, dotcode_factory=self._dotcode_factory, clusters=self._clusters)
00035         if self._pub_string:
00036             self._pub_string.publish(str(current_dotcode))
00037 
00038     def _periodic_callback(self):
00039         pass
00040 
00041     def spin(self):
00042         rospy.spin()
00043 
00044     def loginfo(self, msg):
00045         rospy.loginfo("Conductor Graph To String : %s"%msg)


concert_utilities
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 18:17:52