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 import rospy
00042 import genpy
00043 from rqt_gui_py.plugin import Plugin
00044 from .publisher_widget import PublisherWidget
00045 from rqt_py_common.topic_helpers import get_field_type
00046
00047
00048 class Publisher(Plugin):
00049
00050 def __init__(self, context):
00051 super(Publisher, self).__init__(context)
00052 self.setObjectName('Publisher')
00053
00054
00055 self._widget = PublisherWidget()
00056 self._widget.add_publisher.connect(self.add_publisher)
00057 self._widget.change_publisher.connect(self.change_publisher)
00058 self._widget.publish_once.connect(self.publish_once)
00059 self._widget.remove_publisher.connect(self.remove_publisher)
00060 self._widget.clean_up_publishers.connect(self.clean_up_publishers)
00061 if context.serial_number() > 1:
00062 self._widget.setWindowTitle(
00063 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(
00100 publisher_info['type_name'])
00101 if publisher_info['message_instance'] is None:
00102 return
00103
00104
00105 try:
00106 publisher_info['publisher'] = rospy.Publisher(
00107 publisher_info['topic_name'], type(publisher_info['message_instance']), queue_size=100)
00108 except TypeError:
00109 publisher_info['publisher'] = rospy.Publisher(
00110 publisher_info['topic_name'], type(publisher_info['message_instance']))
00111 publisher_info['timer'] = QTimer(self)
00112
00113
00114 self._publishers[publisher_info['publisher_id']] = publisher_info
00115 self._timeout_mapper.setMapping(publisher_info['timer'], publisher_info['publisher_id'])
00116 publisher_info['timer'].timeout.connect(self._timeout_mapper.map)
00117 if publisher_info['enabled'] and publisher_info['rate'] > 0:
00118 publisher_info['timer'].start(int(1000.0 / publisher_info['rate']))
00119
00120 self._widget.publisher_tree_widget.model().add_publisher(publisher_info)
00121
00122 @Slot(int, str, str, str, object)
00123 def change_publisher(self, publisher_id, topic_name, column_name, new_value, setter_callback):
00124 handler = getattr(self, '_change_publisher_%s' % column_name, None)
00125 if handler is not None:
00126 new_text = handler(self._publishers[publisher_id], topic_name, new_value)
00127 if new_text is not None:
00128 setter_callback(new_text)
00129
00130 def _change_publisher_topic(self, publisher_info, topic_name, new_value):
00131 publisher_info['enabled'] = (new_value and new_value.lower() in ['1', 'true', 'yes'])
00132
00133
00134
00135 if publisher_info['enabled'] and publisher_info['rate'] > 0:
00136 publisher_info['timer'].start(int(1000.0 / publisher_info['rate']))
00137 else:
00138 publisher_info['timer'].stop()
00139 return None
00140
00141 def _change_publisher_type(self, publisher_info, topic_name, new_value):
00142 type_name = new_value
00143
00144 slot_value = self._create_message_instance(type_name)
00145
00146
00147 slot_path = topic_name[len(publisher_info['topic_name']):].strip('/').split('/')
00148 parent_slot = eval('.'.join(["publisher_info['message_instance']"] + slot_path[:-1]))
00149
00150
00151 slot_name = slot_path[-1]
00152 slot_index = parent_slot.__slots__.index(slot_name)
00153
00154
00155 if slot_value is None:
00156 qWarning('Publisher._change_publisher_type(): could not find type: %s' % (type_name))
00157 return parent_slot._slot_types[slot_index]
00158
00159 else:
00160
00161 parent_slot._slot_types[slot_index] = type_name
00162 setattr(parent_slot, slot_name, slot_value)
00163
00164 self._widget.publisher_tree_widget.model().update_publisher(publisher_info)
00165
00166 def _change_publisher_rate(self, publisher_info, topic_name, new_value):
00167 try:
00168 rate = float(new_value)
00169 except Exception:
00170 qWarning('Publisher._change_publisher_rate(): could not parse rate value: %s' %
00171 (new_value))
00172 else:
00173 publisher_info['rate'] = rate
00174
00175
00176
00177 publisher_info['timer'].stop()
00178 if publisher_info['enabled'] and publisher_info['rate'] > 0:
00179 publisher_info['timer'].start(int(1000.0 / publisher_info['rate']))
00180
00181 return '%.2f' % publisher_info['rate']
00182
00183 def _change_publisher_expression(self, publisher_info, topic_name, new_value):
00184 expression = str(new_value)
00185 if len(expression) == 0:
00186 if topic_name in publisher_info['expressions']:
00187 del publisher_info['expressions'][topic_name]
00188
00189
00190
00191 else:
00192 slot_type, is_array = get_field_type(topic_name)
00193 if is_array:
00194 slot_type = list
00195
00196 error_prefix = '# error'
00197 error_prefix_pos = expression.find(error_prefix)
00198 if error_prefix_pos >= 0:
00199 expression = expression[:error_prefix_pos]
00200 success, _ = self._evaluate_expression(expression, slot_type)
00201 if success:
00202 old_expression = publisher_info['expressions'].get(topic_name, None)
00203 publisher_info['expressions'][topic_name] = expression
00204
00205
00206 self._fill_message_slots(
00207 publisher_info['message_instance'], publisher_info['topic_name'],
00208 publisher_info['expressions'], publisher_info['counter'])
00209 try:
00210 publisher_info['message_instance']._check_types()
00211 except Exception as e:
00212 print('serialization error: %s' % e)
00213 if old_expression is not None:
00214 publisher_info['expressions'][topic_name] = old_expression
00215 else:
00216 del publisher_info['expressions'][topic_name]
00217 return '%s %s: %s' % (expression, error_prefix, e)
00218 return expression
00219 else:
00220 return '%s %s evaluating as "%s"' % (expression, error_prefix, slot_type.__name__)
00221
00222 def _extract_array_info(self, type_str):
00223 array_size = None
00224 if '[' in type_str and type_str[-1] == ']':
00225 type_str, array_size_str = type_str.split('[', 1)
00226 array_size_str = array_size_str[:-1]
00227 if len(array_size_str) > 0:
00228 array_size = int(array_size_str)
00229 else:
00230 array_size = 0
00231
00232 return type_str, array_size
00233
00234 def _create_message_instance(self, type_str):
00235 base_type_str, array_size = self._extract_array_info(type_str)
00236
00237 base_message_type = roslib.message.get_message_class(base_type_str)
00238 if base_message_type is None:
00239 print('Could not create message of type "%s".' % base_type_str)
00240 return None
00241
00242 if array_size is not None:
00243 message = []
00244 for _ in range(array_size):
00245 message.append(base_message_type())
00246 else:
00247 message = base_message_type()
00248 return message
00249
00250 def _evaluate_expression(self, expression, slot_type):
00251 successful_eval = True
00252
00253 try:
00254
00255 value = eval(expression, {}, self._eval_locals)
00256 except Exception:
00257 successful_eval = False
00258
00259 if slot_type is str:
00260 if successful_eval:
00261 value = str(value)
00262 else:
00263
00264
00265 value = str(expression)
00266 successful_eval = True
00267
00268 elif successful_eval:
00269 type_set = set((slot_type, type(value)))
00270
00271
00272
00273 if type_set <= set((list, tuple)) or type_set <= set((int, float)):
00274
00275 value = slot_type(value)
00276
00277 if successful_eval and isinstance(value, slot_type):
00278 return True, value
00279 else:
00280 qWarning(
00281 'Publisher._evaluate_expression(): failed to evaluate expression: "%s" as '
00282 'Python type "%s"' % (expression, slot_type.__name__))
00283
00284 return False, None
00285
00286 def _fill_message_slots(self, message, topic_name, expressions, counter):
00287 if topic_name in expressions and len(expressions[topic_name]) > 0:
00288
00289
00290 if hasattr(message, '_type'):
00291 message_type = message._type
00292 else:
00293 message_type = type(message)
00294
00295 self._eval_locals['i'] = counter
00296 success, value = self._evaluate_expression(expressions[topic_name], message_type)
00297 if not success:
00298 value = message_type()
00299 return value
00300
00301
00302 elif hasattr(message, '__slots__'):
00303 for slot_name in message.__slots__:
00304 value = self._fill_message_slots(
00305 getattr(message, slot_name), topic_name + '/' + slot_name, expressions, counter)
00306 if value is not None:
00307 setattr(message, slot_name, value)
00308
00309 elif type(message) in (list, tuple) and (len(message) > 0):
00310 for index, slot in enumerate(message):
00311 value = self._fill_message_slots(
00312 slot, topic_name + '[%d]' % index, expressions, counter)
00313
00314 if not hasattr(message[0], '__slots__') and value is not None:
00315 message[index] = value
00316
00317 return None
00318
00319 @Slot(int)
00320 def publish_once(self, publisher_id):
00321 publisher_info = self._publishers.get(publisher_id, None)
00322 if publisher_info is not None:
00323 publisher_info['counter'] += 1
00324 self._fill_message_slots(
00325 publisher_info['message_instance'],
00326 publisher_info['topic_name'],
00327 publisher_info['expressions'],
00328 publisher_info['counter'])
00329 publisher_info['publisher'].publish(publisher_info['message_instance'])
00330
00331 @Slot(int)
00332 def remove_publisher(self, publisher_id):
00333 publisher_info = self._publishers.get(publisher_id, None)
00334 if publisher_info is not None:
00335 publisher_info['timer'].stop()
00336 publisher_info['publisher'].unregister()
00337 del self._publishers[publisher_id]
00338
00339 def save_settings(self, plugin_settings, instance_settings):
00340 publisher_copies = []
00341 for publisher in self._publishers.values():
00342 publisher_copy = {}
00343 publisher_copy.update(publisher)
00344 publisher_copy['enabled'] = False
00345 del publisher_copy['timer']
00346 del publisher_copy['message_instance']
00347 del publisher_copy['publisher']
00348 publisher_copies.append(publisher_copy)
00349 instance_settings.set_value('publishers', repr(publisher_copies))
00350
00351 def restore_settings(self, plugin_settings, instance_settings):
00352 publishers = eval(instance_settings.value('publishers', '[]'))
00353 for publisher in publishers:
00354 self._add_publisher(publisher)
00355
00356 def clean_up_publishers(self):
00357 self._widget.publisher_tree_widget.model().clear()
00358 for publisher_info in self._publishers.values():
00359 publisher_info['timer'].stop()
00360 publisher_info['publisher'].unregister()
00361 self._publishers = {}
00362
00363 def shutdown_plugin(self):
00364 self._widget.shutdown_plugin()
00365 self.clean_up_publishers()