ros_topics.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Thanks to:
4 # https://github.com/ros-visualization/rqt_common_plugins/blob/groovy-devel/rqt_topic/src/rqt_topic/topic_widget.py
5 import numpy
6 import random
7 
8 import roslib
9 import roslib.message
10 import rospy
11 from opcua import ua, uamethod
12 
13 import ros_actions
14 import ros_server
15 import rostopic
16 
17 
19  def __init__(self, server, parent, idx, topic_name, topic_type):
20  self.server = server
21  self.parent = self.recursive_create_objects(topic_name, idx, parent)
22  self.type_name = topic_type
23  self.name = topic_name
24  self._nodes = {}
25  self.idx = idx
26 
27  self.message_class = None
28  try:
29  self.message_class = roslib.message.get_message_class(topic_type)
31 
32  except rospy.ROSException:
33  self.message_class = None
34  rospy.logfatal("Couldn't find message class for type " + topic_type)
35 
36  self._recursive_create_items(self.parent, idx, topic_name, topic_type, self.message_instance, True)
37 
38  self._subscriber = rospy.Subscriber(self.name, self.message_class, self.message_callback)
39  self._publisher = rospy.Publisher(self.name, self.message_class, queue_size=1)
40  rospy.loginfo("Created ROS Topic with name: " + str(self.name))
41 
42  def _recursive_create_items(self, parent, idx, topic_name, type_name, message, top_level=False):
43  topic_text = topic_name.split('/')[-1]
44  if '[' in topic_text:
45  topic_text = topic_text[topic_text.index('['):]
46 
47  # This here are 'complex datatypes'
48  if hasattr(message, '__slots__') and hasattr(message, '_slot_types'):
49  complex_type = True
50  new_node = parent.add_object(ua.NodeId(topic_name, parent.nodeid.NamespaceIndex, ua.NodeIdType.String),
51  ua.QualifiedName(topic_name, parent.nodeid.NamespaceIndex))
52  new_node.add_property(ua.NodeId(topic_name + ".Type", idx),
53  ua.QualifiedName("Type", parent.nodeid.NamespaceIndex), type_name)
54  if top_level:
55  new_node.add_method(ua.NodeId(topic_name + ".Update", parent.nodeid.NamespaceIndex),
56  ua.QualifiedName("Update", parent.nodeid.NamespaceIndex),
57  self.opcua_update_callback, [], [])
58  for slot_name, type_name_child in zip(message.__slots__, message._slot_types):
59  self._recursive_create_items(new_node, idx, topic_name + '/' + slot_name, type_name_child,
60  getattr(message, slot_name))
61  self._nodes[topic_name] = new_node
62 
63  else:
64  # This are arrays
65  base_type_str, array_size = _extract_array_info(type_name)
66  try:
67  base_instance = roslib.message.get_message_class(base_type_str)()
68  except (ValueError, TypeError):
69  base_instance = None
70 
71  if array_size is not None and hasattr(base_instance, '__slots__'):
72  for index in range(array_size):
73  self._recursive_create_items(parent, idx, topic_name + '[%d]' % index, base_type_str, base_instance)
74  else:
75  new_node = _create_node_with_type(parent, idx, topic_name, topic_text, type_name, array_size)
76  self._nodes[topic_name] = new_node
77 
78  if topic_name in self._nodes and self._nodes[topic_name].get_node_class() == ua.NodeClass.Variable:
79  self._nodes[topic_name].set_writable(True)
80  return
81 
82  def message_callback(self, message):
83  self.update_value(self.name, message)
84 
85  @uamethod
86  def opcua_update_callback(self, parent):
87  try:
88  for nodeName in self._nodes:
89  child = self._nodes[nodeName]
90  name = child.get_display_name().Text
91  if hasattr(self.message_instance, name):
92  if child.get_node_class() == ua.NodeClass.Variable:
93  setattr(self.message_instance, name,
94  correct_type(child, type(getattr(self.message_instance, name))))
95  elif child.get_node_class == ua.NodeClass.Object:
96  setattr(self.message_instance, name, self.create_message_instance(child))
97  self._publisher.publish(self.message_instance)
98  except rospy.ROSException as e:
99  rospy.logerr("Error when updating node " + self.name, e)
100  self.server.server.delete_nodes([self.parent])
101 
102  def update_value(self, topic_name, message):
103  if hasattr(message, '__slots__') and hasattr(message, '_slot_types'):
104  for slot_name in message.__slots__:
105  self.update_value(topic_name + '/' + slot_name, getattr(message, slot_name))
106 
107  elif type(message) in (list, tuple):
108  if (len(message) > 0) and hasattr(message[0], '__slots__'):
109  for index, slot in enumerate(message):
110  if topic_name + '[%d]' % index in self._nodes:
111  self.update_value(topic_name + '[%d]' % index, slot)
112  else:
113  if topic_name in self._nodes:
114  base_type_str, _ = _extract_array_info(
115  self._nodes[topic_name].text(self.type_name))
116  self._recursive_create_items(self._nodes[topic_name], topic_name + '[%d]' % index,
117  base_type_str,
118  slot, None)
119  # remove obsolete children
120  if topic_name in self._nodes:
121  if len(message) < len(self._nodes[topic_name].get_children()):
122  for i in range(len(message), self._nodes[topic_name].childCount()):
123  item_topic_name = topic_name + '[%d]' % i
124  self.recursive_delete_items(self._nodes[item_topic_name])
125  del self._nodes[item_topic_name]
126  else:
127  if topic_name in self._nodes and self._nodes[topic_name] is not None:
128  self._nodes[topic_name].set_value(repr(message))
129 
130  def recursive_delete_items(self, item):
131  self._publisher.unregister()
132  self._subscriber.unregister()
133  for child in item.get_children():
134  self.recursive_delete_items(child)
135  if child in self._nodes:
136  del self._nodes[child]
137  self.server.server.delete_nodes([child])
138  self.server.server.delete_nodes([item])
139  if len(self.parent.get_children()) == 0:
140  self.server.server.delete_nodes([self.parent])
141 
142  def create_message_instance(self, node):
143  for child in node.get_children():
144  name = child.get_display_name().Text
145  if hasattr(self.message_instance, name):
146  if child.get_node_class() == ua.NodeClass.Variable:
147  setattr(self.message_instance, name,
148  correct_type(child, type(getattr(self.message_instance, name))))
149  elif child.get_node_class == ua.NodeClass.Object:
150  setattr(self.message_instance, name, self.create_message_instance(child))
151  return self.message_instance # Converts the value of the node to that specified in the ros message we are trying to fill. Casts python ints
152 
153  def recursive_create_objects(self, topic_name, idx, parent):
154  hierachy = topic_name.split('/')
155  if len(hierachy) == 0 or len(hierachy) == 1:
156  return parent
157  for name in hierachy:
158  if name != '':
159  try:
160  nodewithsamename = self.server.find_topics_node_with_same_name(name, idx)
161  if nodewithsamename is not None:
162  return self.recursive_create_objects(ros_server.nextname(hierachy, hierachy.index(name)), idx,
163  nodewithsamename)
164  else:
165  # if for some reason 2 services with exactly same name are created use hack>: add random int, prob to hit two
166  # same ints 1/10000, should be sufficient
167  newparent = parent.add_object(
168  ua.NodeId(name, parent.nodeid.NamespaceIndex, ua.NodeIdType.String),
169  ua.QualifiedName(name, parent.nodeid.NamespaceIndex))
170  return self.recursive_create_objects(ros_server.nextname(hierachy, hierachy.index(name)), idx,
171  newparent)
172  # thrown when node with parent name is not existent in server
173  except IndexError, common.UaError:
174  newparent = parent.add_object(
175  ua.NodeId(name + str(random.randint(0, 10000)), parent.nodeid.NamespaceIndex,
176  ua.NodeIdType.String),
177  ua.QualifiedName(name, parent.nodeid.NamespaceIndex))
178  return self.recursive_create_objects(ros_server.nextname(hierachy, hierachy.index(name)), idx,
179  newparent)
180 
181  return parent
182 
183 
184 # to unsigned integers as to fulfill ros specification. Currently only uses a few different types,
185 # no other types encountered so far.
186 def correct_type(node, typemessage):
187  data_value = node.get_data_value()
188  result = node.get_value()
189  if isinstance(data_value, ua.DataValue):
190  if typemessage.__name__ == "float":
191  result = numpy.float(result)
192  if typemessage.__name__ == "double":
193  result = numpy.double(result)
194  if typemessage.__name__ == "int":
195  result = int(result) & 0xff
196  else:
197  rospy.logerr("can't convert: " + str(node.get_data_value.Value))
198  return None
199  return result
200 
201 
202 def _extract_array_info(type_str):
203  array_size = None
204  if '[' in type_str and type_str[-1] == ']':
205  type_str, array_size_str = type_str.split('[', 1)
206  array_size_str = array_size_str[:-1]
207  if len(array_size_str) > 0:
208  array_size = int(array_size_str)
209  else:
210  array_size = 0
211 
212  return type_str, array_size
213 
214 
215 def _create_node_with_type(parent, idx, topic_name, topic_text, type_name, array_size):
216  if '[' in type_name:
217  type_name = type_name[:type_name.index('[')]
218 
219  if type_name == 'bool':
220  dv = ua.Variant(False, ua.VariantType.Boolean)
221  elif type_name == 'byte':
222  dv = ua.Variant(0, ua.VariantType.Byte)
223  elif type_name == 'int':
224  dv = ua.Variant(0, ua.VariantType.Int32)
225  elif type_name == 'int8':
226  dv = ua.Variant(0, ua.VariantType.SByte)
227  elif type_name == 'uint8':
228  dv = ua.Variant(0, ua.VariantType.Byte)
229  elif type_name == 'int16':
230  dv = ua.Variant(0, ua.VariantType.Int16)
231  elif type_name == 'uint16':
232  dv = ua.Variant(0, ua.VariantType.UInt16)
233  elif type_name == 'int32':
234  dv = ua.Variant(0, ua.VariantType.Int32)
235  elif type_name == 'uint32':
236  dv = ua.Variant(0, ua.VariantType.UInt32)
237  elif type_name == 'int64':
238  dv = ua.Variant(0, ua.VariantType.Int64)
239  elif type_name == 'uint64':
240  dv = ua.Variant(0, ua.VariantType.UInt64)
241  elif type_name == 'float' or type_name == 'float32' or type_name == 'float64':
242  dv = ua.Variant(0.0, ua.VariantType.Float)
243  elif type_name == 'double':
244  dv = ua.Variant(0.0, ua.VariantType.Double)
245  elif type_name == 'string':
246  dv = ua.Variant('', ua.VariantType.String)
247  else:
248  rospy.logerr("can't create node with type" + str(type_name))
249  return None
250 
251  if array_size is not None:
252  value = []
253  for i in range(array_size):
254  value.append(i)
255  return parent.add_variable(ua.NodeId(topic_name, parent.nodeid.NamespaceIndex),
256  ua.QualifiedName(topic_text, parent.nodeid.NamespaceIndex), dv.Value)
257 
258 
259 # Used to delete obsolete topics
260 def numberofsubscribers(nametolookfor, topicsDict):
261  # rosout only has one subscriber/publisher at all times, so ignore.
262  if nametolookfor != "/rosout":
263  ret = topicsDict[nametolookfor]._subscriber.get_num_connections()
264  else:
265  ret = 2
266  return ret
267 
268 
269 def refresh_topics_and_actions(namespace_ros, server, topicsdict, actionsdict, idx_topics, idx_actions, topics, actions):
270  ros_topics = rospy.get_published_topics(namespace_ros)
271  rospy.logdebug(str(ros_topics))
272  rospy.logdebug(str(rospy.get_published_topics('/move_base_simple')))
273  for topic_name, topic_type in ros_topics:
274  if topic_name not in topicsdict or topicsdict[topic_name] is None:
275  splits = topic_name.split('/')
276  if "cancel" in splits[-1] or "result" in splits[-1] or "feedback" in splits[-1] or "goal" in splits[-1] or "status" in splits[-1]:
277  rospy.logdebug("Found an action: " + str(topic_name))
278  correct_name = ros_actions.get_correct_name(topic_name)
279  if correct_name not in actionsdict:
280  try:
281  rospy.loginfo("Creating Action with name: " + correct_name)
282  actionsdict[correct_name] = ros_actions.OpcUaROSAction(server,
283  actions,
284  idx_actions,
285  correct_name,
286  get_goal_type(correct_name),
287  get_feedback_type(correct_name))
288  except (ValueError, TypeError, AttributeError) as e:
289  print(e)
290  rospy.logerr("Error while creating Action Objects for Action " + topic_name)
291 
292  else:
293  # rospy.loginfo("Ignoring normal topics for debugging...")
294  topic = OpcUaROSTopic(server, topics, idx_topics, topic_name, topic_type)
295  topicsdict[topic_name] = topic
296  elif numberofsubscribers(topic_name, topicsdict) <= 1 and "rosout" not in topic_name:
297  topicsdict[topic_name].recursive_delete_items(server.server.get_node(ua.NodeId(topic_name, idx_topics)))
298  del topicsdict[topic_name]
300 
301  ros_topics = rospy.get_published_topics(namespace_ros)
302  # use to not get dict changed during iteration errors
303  tobedeleted = []
304  for topic_nameOPC in topicsdict:
305  found = False
306  for topicROS, topic_type in ros_topics:
307  if topic_nameOPC == topicROS:
308  found = True
309  if not found:
310  topicsdict[topic_nameOPC].recursive_delete_items(server.get_node(ua.NodeId(topic_nameOPC, idx_topics)))
311  tobedeleted.append(topic_nameOPC)
312  for name in tobedeleted:
313  del topicsdict[name]
314  ros_actions.refresh_dict(namespace_ros, actionsdict, topicsdict, server, idx_actions)
315 
316 
317 def get_feedback_type(action_name):
318  try:
319  type, name, fn = rostopic.get_topic_type(action_name + "/feedback")
320  return type
321  except rospy.ROSException as e:
322  try:
323  type, name, fn = rostopic.get_topic_type(action_name + "/Feedback", e)
324  return type
325  except rospy.ROSException as e2:
326  rospy.logerr("Couldn't find feedback type for action " + action_name, e2)
327  return None
328 
329 
330 def get_goal_type(action_name):
331  try:
332  type, name, fn = rostopic.get_topic_type(action_name + "/goal")
333  return type
334  except rospy.ROSException as e:
335  try:
336  type, name, fn = rostopic.get_topic_type(action_name + "/Goal", e)
337  return type
338  except rospy.ROSException as e2:
339  rospy.logerr("Couldn't find goal type for action " + action_name, e2)
340  return None
def message_callback(self, message)
Definition: ros_topics.py:82
def _recursive_create_items(self, parent, idx, topic_name, type_name, message, top_level=False)
Definition: ros_topics.py:42
def update_value(self, topic_name, message)
Definition: ros_topics.py:102
def get_correct_name(topic_name)
Definition: ros_actions.py:346
def correct_type(node, typemessage)
Definition: ros_topics.py:186
def _extract_array_info(type_str)
Definition: ros_topics.py:202
def __init__(self, server, parent, idx, topic_name, topic_type)
Definition: ros_topics.py:19
def numberofsubscribers(nametolookfor, topicsDict)
Definition: ros_topics.py:260
def nextname(hierachy, index_of_last_processed)
Definition: ros_server.py:15
def opcua_update_callback(self, parent)
Definition: ros_topics.py:86
def get_goal_type(action_name)
Definition: ros_topics.py:330
def refresh_dict(namespace_ros, actionsdict, topicsdict, server, idx_actions)
Definition: ros_actions.py:407
def recursive_create_objects(self, topic_name, idx, parent)
Definition: ros_topics.py:153
def create_message_instance(self, node)
Definition: ros_topics.py:142
def get_feedback_type(action_name)
Definition: ros_topics.py:317
def recursive_delete_items(self, item)
Definition: ros_topics.py:130
def refresh_topics_and_actions(namespace_ros, server, topicsdict, actionsdict, idx_topics, idx_actions, topics, actions)
Definition: ros_topics.py:269
def own_rosnode_cleanup()
Definition: ros_server.py:27
def _create_node_with_type(parent, idx, topic_name, topic_text, type_name, array_size)
Definition: ros_topics.py:215


ros_opcua_impl_python_opcua
Author(s): Denis Štogl , Daniel Draper
autogenerated on Tue Jan 19 2021 03:12:44