00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 from __future__ import division
00034 import math
00035 import random
00036 import time
00037
00038 from python_qt_binding.QtCore import Slot, QSignalMapper, QTimer, qWarning
00039
00040 import roslib
00041 roslib.load_manifest('rqt_publisher')
00042 import rospy
00043 import genpy
00044 from rqt_gui_py.plugin import Plugin
00045 from .publisher_widget import PublisherWidget
00046 from rqt_py_common.topic_helpers import get_field_type
00047
00048
00049 class Publisher(Plugin):
00050
00051 def __init__(self, context):
00052 super(Publisher, self).__init__(context)
00053 self.setObjectName('Publisher')
00054
00055
00056 self._widget = PublisherWidget()
00057 self._widget.add_publisher.connect(self.add_publisher)
00058 self._widget.change_publisher.connect(self.change_publisher)
00059 self._widget.publish_once.connect(self.publish_once)
00060 self._widget.remove_publisher.connect(self.remove_publisher)
00061 self._widget.clean_up_publishers.connect(self.clean_up_publishers)
00062 if context.serial_number() > 1:
00063 self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00064
00065
00066 self._eval_locals = {'i': 0}
00067 for module in (math, random, time):
00068 self._eval_locals.update(module.__dict__)
00069 self._eval_locals['genpy'] = genpy
00070 del self._eval_locals['__name__']
00071 del self._eval_locals['__doc__']
00072
00073 self._publishers = {}
00074 self._id_counter = 0
00075
00076 self._timeout_mapper = QSignalMapper(self)
00077 self._timeout_mapper.mapped[int].connect(self.publish_once)
00078
00079
00080 context.add_widget(self._widget)
00081
00082 @Slot(str, str, float, bool)
00083 def add_publisher(self, topic_name, type_name, rate, enabled):
00084 publisher_info = {
00085 'topic_name': str(topic_name),
00086 'type_name': str(type_name),
00087 'rate': float(rate),
00088 'enabled': bool(enabled),
00089 }
00090 self._add_publisher(publisher_info)
00091
00092 def _add_publisher(self, publisher_info):
00093 publisher_info['publisher_id'] = self._id_counter
00094 self._id_counter += 1
00095 publisher_info['counter'] = 0
00096 publisher_info['enabled'] = publisher_info.get('enabled', False)
00097 publisher_info['expressions'] = publisher_info.get('expressions', {})
00098
00099 publisher_info['message_instance'] = self._create_message_instance(publisher_info['type_name'])
00100 if publisher_info['message_instance'] is None:
00101 return
00102
00103
00104 publisher_info['publisher'] = rospy.Publisher(publisher_info['topic_name'], type(publisher_info['message_instance']))
00105 publisher_info['timer'] = QTimer(self)
00106
00107
00108 self._publishers[publisher_info['publisher_id']] = publisher_info
00109 self._timeout_mapper.setMapping(publisher_info['timer'], publisher_info['publisher_id'])
00110 publisher_info['timer'].timeout.connect(self._timeout_mapper.map)
00111 if publisher_info['enabled'] and publisher_info['rate'] > 0:
00112 publisher_info['timer'].start(int(1000.0 / publisher_info['rate']))
00113
00114 self._widget.publisher_tree_widget.model().add_publisher(publisher_info)
00115
00116 @Slot(int, str, str, str, object)
00117 def change_publisher(self, publisher_id, topic_name, column_name, new_value, setter_callback):
00118 handler = getattr(self, '_change_publisher_%s' % column_name, None)
00119 if handler is not None:
00120 new_text = handler(self._publishers[publisher_id], topic_name, new_value)
00121 if new_text is not None:
00122 setter_callback(new_text)
00123
00124 def _change_publisher_topic(self, publisher_info, topic_name, new_value):
00125 publisher_info['enabled'] = (new_value and new_value.lower() in ['1', 'true', 'yes'])
00126
00127 if publisher_info['enabled'] and publisher_info['rate'] > 0:
00128 publisher_info['timer'].start(int(1000.0 / publisher_info['rate']))
00129 else:
00130 publisher_info['timer'].stop()
00131 return None
00132
00133 def _change_publisher_type(self, publisher_info, topic_name, new_value):
00134 type_name = new_value
00135
00136 slot_value = self._create_message_instance(type_name)
00137
00138
00139 slot_path = topic_name[len(publisher_info['topic_name']):].strip('/').split('/')
00140 parent_slot = eval('.'.join(["publisher_info['message_instance']"] + slot_path[:-1]))
00141
00142
00143 slot_name = slot_path[-1]
00144 slot_index = parent_slot.__slots__.index(slot_name)
00145
00146
00147 if slot_value is None:
00148 qWarning('Publisher._change_publisher_type(): could not find type: %s' % (type_name))
00149 return parent_slot._slot_types[slot_index]
00150
00151 else:
00152
00153 parent_slot._slot_types[slot_index] = type_name
00154 setattr(parent_slot, slot_name, slot_value)
00155
00156 self._widget.publisher_tree_widget.model().update_publisher(publisher_info)
00157
00158 def _change_publisher_rate(self, publisher_info, topic_name, new_value):
00159 try:
00160 rate = float(new_value)
00161 except Exception:
00162 qWarning('Publisher._change_publisher_rate(): could not parse rate value: %s' % (new_value))
00163 else:
00164 publisher_info['rate'] = rate
00165
00166 publisher_info['timer'].stop()
00167 if publisher_info['enabled'] and publisher_info['rate'] > 0:
00168 publisher_info['timer'].start(int(1000.0 / publisher_info['rate']))
00169
00170 return '%.2f' % publisher_info['rate']
00171
00172 def _change_publisher_expression(self, publisher_info, topic_name, new_value):
00173 expression = str(new_value)
00174 if len(expression) == 0:
00175 if topic_name in publisher_info['expressions']:
00176 del publisher_info['expressions'][topic_name]
00177
00178 else:
00179 slot_type, is_array = get_field_type(topic_name)
00180 if is_array:
00181 slot_type = list
00182
00183 error_prefix = '# error'
00184 error_prefix_pos = expression.find(error_prefix)
00185 if error_prefix_pos >= 0:
00186 expression = expression[:error_prefix_pos]
00187 success, _ = self._evaluate_expression(expression, slot_type)
00188 if success:
00189 old_expression = publisher_info['expressions'].get(topic_name, None)
00190 publisher_info['expressions'][topic_name] = expression
00191
00192 self._fill_message_slots(publisher_info['message_instance'], publisher_info['topic_name'], publisher_info['expressions'], publisher_info['counter'])
00193 try:
00194 publisher_info['message_instance']._check_types()
00195 except Exception, e:
00196 error_str = str(e)
00197 print 'serialization error:', error_str
00198 if old_expression is not None:
00199 publisher_info['expressions'][topic_name] = old_expression
00200 else:
00201 del publisher_info['expressions'][topic_name]
00202 return '%s %s: %s' % (expression, error_prefix, error_str)
00203 return expression
00204 else:
00205 return '%s %s evaluating as "%s"' % (expression, error_prefix, slot_type.__name__)
00206
00207 def _extract_array_info(self, type_str):
00208 array_size = None
00209 if '[' in type_str and type_str[-1] == ']':
00210 type_str, array_size_str = type_str.split('[', 1)
00211 array_size_str = array_size_str[:-1]
00212 if len(array_size_str) > 0:
00213 array_size = int(array_size_str)
00214 else:
00215 array_size = 0
00216
00217 return type_str, array_size
00218
00219 def _create_message_instance(self, type_str):
00220 base_type_str, array_size = self._extract_array_info(type_str)
00221
00222 base_message_type = roslib.message.get_message_class(base_type_str)
00223 if base_message_type is None:
00224 print 'Could not create message of type "%s".' % base_type_str
00225 return None
00226
00227 if array_size is not None:
00228 message = []
00229 for _ in range(array_size):
00230 message.append(base_message_type())
00231 else:
00232 message = base_message_type()
00233 return message
00234
00235 def _evaluate_expression(self, expression, slot_type):
00236 successful_eval = True
00237
00238 try:
00239
00240 value = eval(expression, {}, self._eval_locals)
00241 except Exception:
00242 successful_eval = False
00243
00244 if slot_type is str:
00245 if successful_eval:
00246 value = str(value)
00247 else:
00248
00249 value = str(expression)
00250 successful_eval = True
00251
00252 elif successful_eval:
00253 type_set = set((slot_type, type(value)))
00254
00255
00256 if type_set <= set((list, tuple)) or type_set <= set((int, float)):
00257
00258 value = slot_type(value)
00259
00260 if successful_eval and isinstance(value, slot_type):
00261 return True, value
00262 else:
00263 qWarning('Publisher._evaluate_expression(): failed to evaluate expression: "%s" as Python type "%s"' % (expression, slot_type.__name__))
00264
00265 return False, None
00266
00267 def _fill_message_slots(self, message, topic_name, expressions, counter):
00268 if topic_name in expressions and len(expressions[topic_name]) > 0:
00269
00270
00271 if hasattr(message, '_type'):
00272 message_type = message._type
00273 else:
00274 message_type = type(message)
00275
00276 self._eval_locals['i'] = counter
00277 success, value = self._evaluate_expression(expressions[topic_name], message_type)
00278 if not success:
00279 value = message_type()
00280 return value
00281
00282
00283 elif hasattr(message, '__slots__'):
00284 for slot_name in message.__slots__:
00285 value = self._fill_message_slots(getattr(message, slot_name), topic_name + '/' + slot_name, expressions, counter)
00286 if value is not None:
00287 setattr(message, slot_name, value)
00288
00289 elif type(message) in (list, tuple) and (len(message) > 0) and hasattr(message[0], '__slots__'):
00290 for index, slot in enumerate(message):
00291 self._fill_message_slots(slot, topic_name + '[%d]' % index, expressions, counter)
00292
00293 return None
00294
00295 @Slot(int)
00296 def publish_once(self, publisher_id):
00297 publisher_info = self._publishers.get(publisher_id, None)
00298 if publisher_info is not None:
00299 publisher_info['counter'] += 1
00300 self._fill_message_slots(publisher_info['message_instance'], publisher_info['topic_name'], publisher_info['expressions'], publisher_info['counter'])
00301 publisher_info['publisher'].publish(publisher_info['message_instance'])
00302
00303 @Slot(int)
00304 def remove_publisher(self, publisher_id):
00305 publisher_info = self._publishers.get(publisher_id, None)
00306 if publisher_info is not None:
00307 publisher_info['timer'].stop()
00308 publisher_info['publisher'].unregister()
00309 del self._publishers[publisher_id]
00310
00311 def save_settings(self, plugin_settings, instance_settings):
00312 publisher_copies = []
00313 for publisher in self._publishers.values():
00314 publisher_copy = {}
00315 publisher_copy.update(publisher)
00316 publisher_copy['enabled'] = False
00317 del publisher_copy['timer']
00318 del publisher_copy['message_instance']
00319 del publisher_copy['publisher']
00320 publisher_copies.append(publisher_copy)
00321 instance_settings.set_value('publishers', repr(publisher_copies))
00322
00323 def restore_settings(self, plugin_settings, instance_settings):
00324 publishers = eval(instance_settings.value('publishers', '[]'))
00325 for publisher in publishers:
00326 self._add_publisher(publisher)
00327
00328 def clean_up_publishers(self):
00329 self._widget.publisher_tree_widget.model().clear()
00330 for publisher_info in self._publishers.values():
00331 publisher_info['timer'].stop()
00332 publisher_info['publisher'].unregister()
00333 self._publishers = {}
00334
00335 def shutdown_plugin(self):
00336 self._widget.shutdown_plugin()
00337 self.clean_up_publishers()