ros_actions.py
Go to the documentation of this file.
1 # !/usr/bin/python
2 # thanks to https://github.com/ros-visualization/rqt_common_plugins/blob/groovy-devel/rqt_action/src/rqt_action/action_plugin.py
3 import string
4 import random
5 from pydoc import locate
6 
7 import actionlib
8 import roslib
9 import rospy
10 from opcua import ua, common
11 from opcua import uamethod
12 from opcua.ua.uaerrors import UaError
13 from roslib import message
14 
15 import ros_server
16 import ros_services
17 import ros_topics
18 
19 
21  def __init__(self, server, parent, idx, name, action_type, feedback_type):
22  self.server = server
23  self.idx = idx
24  self.name = name
25  self.type = action_type.split("/")[0]
26  self.feedback_type = feedback_type
27  self._feedback_nodes = {}
28  goal_name = "_" + action_type.split("/")[-1]
29  msg_name = goal_name.replace("Goal", "")
30  class_name = msg_name.replace("_", "", 1)
31  rospy.logdebug("Trying to find module with name: " + self.type + ".msg." + goal_name.replace("Goal", ""))
32  actionspec = locate(self.type + ".msg." + msg_name)
33  rospy.logdebug("We are creating action: " + self.name)
34  rospy.logdebug("We have type: " + self.type)
35  rospy.logdebug("We have msg name: " + msg_name)
36  rospy.logdebug("We have class name: " + class_name)
37  rospy.logdebug("We have goal name: " + goal_name)
38  rospy.logdebug("We have goal class name: " + goal_name.replace("_", "", 1))
39 
40  goalspec = locate(self.type + ".msg." + goal_name)
41  rospy.logdebug("found goalspec")
42  self.goal_class = getattr(goalspec, goal_name.replace("_", "", 1))
43  # malformed move_base_simple Action hack
44  if 'move_base_simple' in self.name:
45  self.goal_instance = self.goal_class()
46  else:
47  self.goal_instance = self.goal_class().goal
48  rospy.logdebug("found goal_instance " + str(self.goal_instance))
49  try:
50  self.client = actionlib.SimpleActionClient(self.get_ns_name(), getattr(actionspec, class_name))
51  rospy.logdebug("We have created a SimpleActionClient for action " + self.name)
52  except actionlib.ActionException as e:
53  rospy.logerr("Error when creating ActionClient for action " + self.name, e)
54  rospy.logdebug("Creating parent objects for action " + str(self.name))
55  self.parent = self.recursive_create_objects(name, idx, parent)
56  rospy.logdebug("Found parent for action: " + str(self.parent))
57  rospy.logdebug("Creating main node with name " + self.name.split("/")[-1])
58  # parent is our main node, this means our parent in log message above was actionsObject
59  if self.name.split("/")[-1] == self.parent.nodeid.Identifier:
60  self.main_node = self.parent
61  else:
62  self.main_node = self.parent.add_object(
63  ua.NodeId(self.name.split("/")[-1], self.parent.nodeid.NamespaceIndex, ua.NodeIdType.String),
64  ua.QualifiedName(self.name.split("/")[-1], self.parent.nodeid.NamespaceIndex))
65  rospy.logdebug("Created Main Node under parent!")
66  self.result = self.main_node.add_object(
67  ua.NodeId(self.name + "_result", self.main_node.nodeid.NamespaceIndex, ua.NodeIdType.String),
68  ua.QualifiedName("result", self.main_node.nodeid.NamespaceIndex))
69  self.result_node = ros_topics._create_node_with_type(self.result, self.idx, self.name + "_result_value",
70  self.name + "_result_value",
71  "string", -1)
72 
73  self.result_node.set_value("No goal completed yet")
74  rospy.logdebug("Created result node")
75  self.goal = self.main_node.add_object(
76  ua.NodeId(self.name + "_goal", self.main_node.nodeid.NamespaceIndex, ua.NodeIdType.String),
77  ua.QualifiedName("goal", parent.nodeid.NamespaceIndex))
78  self.goal_node = self.goal.add_method(idx, self.name + "_send_goal", self.send_goal,
79  getargarray(self.goal_instance), [])
80 
81  self.goal_cancel = self.goal.add_method(idx, self.name + "_cancel_goal", self.cancel_goal, [], [])
82 
83  rospy.logdebug("Created goal node")
84 
85  self.feedback = self.main_node.add_object(
86  ua.NodeId(self.name + "feedback", self.main_node.nodeid.NamespaceIndex, ua.NodeIdType.String),
87  ua.QualifiedName("feedback", self.main_node.nodeid.NamespaceIndex))
88  rospy.logdebug("Created feedback node")
89  if self.feedback_type is not None:
90  try:
91  rospy.logdebug("We are trying to create Feedback for feedback type: " + self.feedback_type)
92  self.feedback_message_class = roslib.message.get_message_class(self.feedback_type)
94  rospy.logdebug("Created feedback message instance")
95 
96  except rospy.ROSException:
97  self.message_class = None
98  rospy.logerror("Didn't find feedback message class for type " + self.feedback_type)
99 
100  self._recursive_create_feedback_items(self.feedback, self.name + "/feedback", self.feedback_type,
101  getattr(self.feedback_message_instance, "feedback"))
102 
103  self.status = self.main_node.add_object(
104  ua.NodeId(self.name + "status", self.main_node.nodeid.NamespaceIndex, ua.NodeIdType.String),
105  ua.QualifiedName("status", self.main_node.nodeid.NamespaceIndex))
106  self.status_node = ros_topics._create_node_with_type(self.status, self.idx, self.name + "_status",
107  self.name + "_status",
108  "string", -1)
109  self.status_node.set_value("No goal sent yet")
110  rospy.loginfo("Created ROS Action with name: %s", self.name)
111 
112  def message_callback(self, message):
113  self.update_value(self.name + "/feedback", message)
114 
115  def update_value(self, topic_name, message):
116  if hasattr(message, '__slots__') and hasattr(message, '_slot_types'):
117  for slot_name in message.__slots__:
118  self.update_value(topic_name + '/' + slot_name, getattr(message, slot_name))
119 
120  elif type(message) in (list, tuple):
121  if (len(message) > 0) and hasattr(message[0], '__slots__'):
122  for index, slot in enumerate(message):
123  if topic_name + '[%d]' % index in self._feedback_nodes:
124  self.update_value(topic_name + '[%d]' % index, slot)
125  else:
126  if topic_name in self._feedback_nodes:
127  base_type_str, _ = ros_topics._extract_array_info(
128  self._feedback_nodes[topic_name].text(self.feedback_type))
129  self._recursive_create_items(self._feedback_nodes[topic_name], topic_name + '[%d]' % index,
130  base_type_str,
131  slot, None)
132  # remove obsolete children
133  if topic_name in self._feedback_nodes:
134  if len(message) < len(self._feedback_nodes[topic_name].get_children()):
135  for i in range(len(message), self._feedback_nodes[topic_name].childCount()):
136  item_topic_name = topic_name + '[%d]' % i
137  self.recursive_delete_items(self._feedback_nodes[item_topic_name])
138  del self._feedback_nodes[item_topic_name]
139  else:
140  if topic_name in self._feedback_nodes and self._feedback_nodes[topic_name] is not None:
141  self._feedback_nodes[topic_name].set_value(repr(message))
142 
143  @uamethod
144  def cancel_goal(self, parent, *inputs):
145  # rospy.logdebug("cancelling goal " + self.name)
146  try:
147  self.client.cancel_all_goals()
148  self.update_state()
149  except (rospy.ROSException, UaError) as e:
150  rospy.logerr("Error when cancelling a goal for " + self.name, e)
151 
152  def recursive_create_objects(self, topic_name, idx, parent):
153  rospy.logdebug("reached parent object creation! current parent: " + str(parent))
154  hierachy = topic_name.split('/')
155  rospy.logdebug("Current hierachy: " + str(hierachy))
156  if len(hierachy) == 0 or len(hierachy) == 1:
157  return parent
158  for name in hierachy:
159  rospy.logdebug("current name: " + str(name))
160  if name != '':
161  try:
162  nodewithsamename = self.server.find_action_node_with_same_name(name, idx)
163  if nodewithsamename is not None:
164  rospy.logdebug("Found node with same name, is now new parent")
165  return self.recursive_create_objects(ros_server.nextname(hierachy, hierachy.index(name)), idx,
166  nodewithsamename)
167  else:
168  # if for some reason 2 services with exactly same name are created use hack>: add random int, prob to hit two
169  # same ints 1/10000, should be sufficient
170  newparent = parent.add_object(
171  ua.NodeId(name, parent.nodeid.NamespaceIndex, ua.NodeIdType.String),
172  ua.QualifiedName(name, parent.nodeid.NamespaceIndex))
173  return self.recursive_create_objects(ros_server.nextname(hierachy, hierachy.index(name)), idx,
174  newparent)
175  # thrown when node with parent name is not existent in server
176  except IndexError, UaError:
177  newparent = parent.add_object(
178  ua.NodeId(name + str(random.randint(0, 10000)), parent.nodeid.NamespaceIndex,
179  ua.NodeIdType.String),
180  ua.QualifiedName(name, parent.nodeid.NamespaceIndex))
181  return self.recursive_create_objects(ros_server.nextname(hierachy, hierachy.index(name)), idx,
182  newparent)
183 
184  return parent
185 
186  def _recursive_create_feedback_items(self, parent, feedback_topic_name, type_name, feedback_message):
187  idx = self.idx
188  topic_text = feedback_topic_name.split('/')[-1]
189  if '[' in topic_text:
190  topic_text = topic_text[topic_text.index('['):]
191 
192  # This here are 'complex data'
193  if hasattr(feedback_message, '__slots__') and hasattr(feedback_message, '_slot_types'):
194  complex_type = True
195  new_node = parent.add_object(
196  ua.NodeId(feedback_topic_name, parent.nodeid.NamespaceIndex, ua.NodeIdType.String),
197  ua.QualifiedName(feedback_topic_name, parent.nodeid.NamespaceIndex))
198 
199  for slot_name, type_name_child in zip(feedback_message.__slots__, feedback_message._slot_types):
200  self._recursive_create_feedback_items(new_node, feedback_topic_name + '/' + slot_name, type_name_child,
201  getattr(feedback_message, slot_name))
202  self._feedback_nodes[feedback_topic_name] = new_node
203 
204  else:
205  # This are arrays
206  base_type_str, array_size = ros_topics._extract_array_info(type_name)
207  try:
208  base_instance = roslib.message.get_message_class(base_type_str)()
209  except (ValueError, TypeError):
210  base_instance = None
211 
212  if array_size is not None and hasattr(base_instance, '__slots__'):
213  for index in range(array_size):
214  self._recursive_create_feedback_items(parent, feedback_topic_name + '[%d]' % index, base_type_str,
215  base_instance)
216  else:
217  new_node = ros_topics._create_node_with_type(parent, idx, feedback_topic_name, topic_text, type_name,
218  array_size)
219  new_node.set_writable(True)
220  self._feedback_nodes[feedback_topic_name] = new_node
221  return
222 
223  # namespace
224  def get_ns_name(self):
225  splits = self.name.split("/")
226  ns = splits[1:]
227  res = ""
228  for split in ns:
229  res += split + "/"
230  rospy.logdebug("Created ns name: " + res[:-1])
231  return str(res[:-1])
232 
233  @uamethod
234  def send_goal(self, parent, *inputs):
235  rospy.loginfo("Sending Goal for " + self.name)
236  try:
237  goal_msg = self.create_message_instance(inputs, self.goal_instance)
238  if 'move_base' in self.name:
239  rospy.loginfo("setting frame_id for move_base malformation")
240  try:
241  target_pose = getattr(goal_msg, "target_pose")
242  header = getattr(target_pose, "header")
243  setattr(header, "frame_id", "map")
244  setattr(target_pose, "header", header)
245  except AttributeError as e:
246  rospy.logerr("Error occured when setting frame_id", e)
247  rospy.loginfo("Created Message Instance for goal-send: " + str(goal_msg))
248  self.client.send_goal(goal_msg, done_cb=self.update_result, feedback_cb=self.update_feedback,
249  active_cb=self.update_state)
250  return
251  except Exception as e:
252  rospy.logerr("Error occured during goal sending for Action " + str(self.name))
253  print(e)
254 
255  def create_message_instance(self, inputs, sample):
256  rospy.logdebug("Creating message for goal call")
257  already_set = []
258  if isinstance(inputs, tuple):
259  arg_counter = 0
260  object_counter = 0
261  while arg_counter < len(inputs) and object_counter < len(sample.__slots__):
262  cur_arg = inputs[arg_counter]
263  cur_slot = sample.__slots__[object_counter]
264  # ignore header for malformed move_base_goal, as header shouldnt be in sent message
265  while cur_slot == 'header':
266  rospy.logdebug("ignoring header")
267  object_counter += 1
268  if object_counter < len(sample.__slots__):
269  cur_slot = sample.__slots__[object_counter]
270  real_slot = getattr(sample, cur_slot)
271  rospy.lodebug(
272  "cur_arg: " + str(cur_arg) + " cur_slot_name: " + str(cur_slot) + " real slot content: " + str(
273  real_slot))
274  if hasattr(real_slot, '_type'):
275  rospy.logdebug("We found an object with name " + str(cur_slot) + ", creating it recursively")
276  arg_counter_before = arg_counter
277  already_set, arg_counter = self.create_object_instance(already_set, real_slot, cur_slot,
278  arg_counter, inputs, sample)
279  if arg_counter != arg_counter_before:
280  object_counter += 1
281  rospy.logdebug("completed object, object counter: " + str(object_counter) + " len(object): " + str(
282  len(sample.__slots__)))
283  else:
284  already_set.append(cur_slot)
285  # set the attribute in the request
286  setattr(sample, cur_slot, cur_arg)
287  arg_counter += 1
288  object_counter += 1
289 
290  return sample
291 
292  def create_object_instance(self, already_set, object, name, counter, inputs, parent):
293  rospy.logdebug("Create Object Instance Notify")
294  object_counter = 0
295  while object_counter < len(object.__slots__) and counter < len(inputs):
296  cur_arg = inputs[counter]
297  cur_slot = object.__slots__[object_counter]
298  # ignore header for malformed move_base_goal, as header shouldnt be in sent message
299  while cur_slot == 'header':
300  rospy.logdebug("ignoring header")
301  object_counter += 1
302  if object_counter < len(object.__slots__):
303  cur_slot = object.__slots__[object_counter]
304  else:
305  return already_set, counter
306  real_slot = getattr(object, cur_slot)
307  rospy.logdebug(
308  "cur_arg: " + str(cur_arg) + " cur_slot_name: " + str(cur_slot) + " real slot content: " + str(
309  real_slot))
310  if hasattr(real_slot, '_type'):
311  rospy.logdebug("Recursive Object found in request/response of service call")
312  already_set, counter = self.create_object_instance(already_set, real_slot, cur_slot, counter, inputs,
313  object)
314  object_counter += 1
315  else:
316  already_set.append(cur_slot)
317  setattr(object, cur_slot, cur_arg)
318  object_counter += 1
319  counter += 1
320  # sets the object as an attribute in the request were trying to build
321  setattr(parent, name, object)
322  return already_set, counter
323 
324  def recursive_delete_items(self, item):
325  self.client.cancel_all_goals()
326  for child in item.get_children():
327  self.recursive_delete_items(child)
328  self.server.server.delete_nodes([child])
329  self.server.server.delete_nodes([self.result, self.result_node, self.goal_node, self.goal, self.parent])
331 
332  def update_result(self, state, result):
333  rospy.logdebug("updated result cb reached")
334  self.status_node.set_value(map_status_to_string(state))
335  self.result_node.set_value(repr(result))
336 
337  def update_state(self):
338  rospy.logdebug("updated state cb reached")
339  self.status_node.set_value(repr(self.client.get_goal_status_text()))
340 
341  def update_feedback(self, feedback):
342  rospy.logdebug("updated feedback cb reached")
343  self.message_callback(feedback)
344 
345 
346 def get_correct_name(topic_name):
347  rospy.logdebug("getting correct name for: " + str(topic_name))
348  splits = topic_name.split('/')
349  return string.join(splits[0:-1], '/')
350 
351 
352 def getargarray(goal_class):
353  array = []
354  for slot_name in goal_class.__slots__:
355  if slot_name != 'header':
356  slot = getattr(goal_class, slot_name)
357  if hasattr(slot, '_type'):
358  array_to_merge = getargarray(slot)
359  array.extend(array_to_merge)
360  else:
361  if isinstance(slot, list):
362  rospy.logdebug("Found an Array Argument!")
363  arg = ua.Argument()
364  arg.Name = slot_name
365  arg.DataType = ua.NodeId(ros_services.getobjectidfromtype("array"))
366  arg.ValueRank = -1
367  arg.ArrayDimensions = []
368  arg.Description = ua.LocalizedText("Array")
369  else:
370  arg = ua.Argument()
371  if hasattr(goal_class, "__name__"):
372  arg.Name = goal_class.__name__ + slot_name
373  else:
374  arg.Name = slot_name
375  arg.DataType = ua.NodeId(ros_services.getobjectidfromtype(type(slot).__name__))
376  arg.ValueRank = -1
377  arg.ArrayDimensions = []
378  arg.Description = ua.LocalizedText(slot_name)
379  array.append(arg)
380 
381  return array
382 
383 
385  if param == 9:
386  return "Goal LOST"
387  elif param == 8:
388  return "Goal RECALLED"
389  elif param == 7:
390  return "Goal RECALLING"
391  elif param == 6:
392  return "Goal PREEMPTING"
393  elif param == 5:
394  return "Goal REJECTED"
395  elif param == 4:
396  return "Goal ABORTED"
397  elif param == 3:
398  return "Goal SUCEEDED"
399  elif param == 2:
400  return "Goal PREEMPTED"
401  elif param == 1:
402  return "Goal ACTIVE"
403  elif param == 0:
404  return "Goal PENDING"
405 
406 
407 def refresh_dict(namespace_ros, actionsdict, topicsdict, server, idx_actions):
408  topics = rospy.get_published_topics(namespace_ros)
409  tobedeleted = []
410  for actionNameOPC in actionsdict:
411  found = False
412  for topicROS, topic_type in topics:
414  if actionNameOPC in topicROS:
415  found = True
416  if not found:
417  actionsdict[actionNameOPC].recursive_delete_items(actionsdict[actionNameOPC].parent)
418  tobedeleted.append(actionNameOPC)
419  rospy.logdebug("deleting action: " + actionNameOPC)
421  for name in tobedeleted:
422  del actionsdict[name]
def map_status_to_string(param)
Definition: ros_actions.py:384
def recursive_delete_items(self, item)
Definition: ros_actions.py:324
def create_message_instance(self, inputs, sample)
Definition: ros_actions.py:255
def update_value(self, topic_name, message)
Definition: ros_actions.py:115
def get_correct_name(topic_name)
Definition: ros_actions.py:346
def _extract_array_info(type_str)
Definition: ros_topics.py:202
def nextname(hierachy, index_of_last_processed)
Definition: ros_server.py:15
def _recursive_create_feedback_items(self, parent, feedback_topic_name, type_name, feedback_message)
Definition: ros_actions.py:186
def recursive_create_objects(self, topic_name, idx, parent)
Definition: ros_actions.py:152
def getobjectidfromtype(type_name)
def update_feedback(self, feedback)
Definition: ros_actions.py:341
def refresh_dict(namespace_ros, actionsdict, topicsdict, server, idx_actions)
Definition: ros_actions.py:407
def create_object_instance(self, already_set, object, name, counter, inputs, parent)
Definition: ros_actions.py:292
def update_result(self, state, result)
Definition: ros_actions.py:332
def send_goal(self, parent, inputs)
Definition: ros_actions.py:234
def __init__(self, server, parent, idx, name, action_type, feedback_type)
Definition: ros_actions.py:21
def cancel_goal(self, parent, inputs)
Definition: ros_actions.py:144
def getargarray(goal_class)
Definition: ros_actions.py:352
def own_rosnode_cleanup()
Definition: ros_server.py:27
def message_callback(self, message)
Definition: ros_actions.py:112
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