simple_script_server.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import time
19 import datetime
20 import os
21 import sys
22 import math
23 import threading
24 import numpy
25 import itertools
26 import six
27 from threading import Thread
28 
29 try: # izip is only available in 2.x
30  from itertools import izip as zip
31 except ImportError:
32  pass
33 
34 # graph includes
35 import pygraphviz as pgv
36 
37 # ROS imports
38 import rospy
39 import actionlib
40 from actionlib.msg import TestAction, TestGoal
41 from actionlib_msgs.msg import GoalStatus
42 
43 from urdf_parser_py.urdf import URDF
44 
45 # msg imports
46 from std_msgs.msg import String,ColorRGBA
47 from std_srvs.srv import Trigger
48 from sensor_msgs.msg import JointState
49 from geometry_msgs.msg import PoseStamped, Twist
50 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
51 from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
52 from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryGoal
53 from tf.transformations import quaternion_from_euler
54 
55 # care-o-bot includes
56 from cob_actions.msg import SetStringAction, SetStringGoal
57 from cob_sound.msg import SayAction, SayGoal, PlayAction, PlayGoal
58 from cob_script_server.msg import ScriptState
59 from cob_light.msg import LightMode, LightModes, SetLightModeGoal, SetLightModeAction
60 from cob_mimic.msg import SetMimicGoal, SetMimicAction
61 
62 graph=""
63 graph_wait_list=[]
64 ah_counter = 0
65 graph = pgv.AGraph()
66 graph.node_attr['shape']='box'
67 last_node = "Start"
68 
69 ## Script class from which all script inherit.
70 #
71 # Implements basic functionalities for all scripts.
72 class script():
73  def __init__(self):
74  # use filename as nodename
75  filename = os.path.basename(sys.argv[0])
76  self.basename, extension = os.path.splitext(filename)
77  rospy.init_node(self.basename)
78  self.graph_pub = rospy.Publisher("/script_server/graph", String, queue_size=1)
79 
80  ## Dummy function for initialization
81  def Initialize(self):
82  pass
83 
84  ## Dummy function for main run function
85  def Run(self):
86  pass
87 
88  ## Function to start the script
89  #
90  # First does a simulated turn and then calls Initialize() and Run().
91  def Start(self):
92  self.Parse()
93  global ah_counter
94  ah_counter = 0
96  rospy.loginfo("Starting <<%s>> script...",self.basename)
97  self.Initialize()
98  self.Run()
99  # wait until last threaded action finishes
100  rospy.loginfo("Wait for script to finish...")
101  while ah_counter != 0:
102  rospy.sleep(1)
103  rospy.loginfo("...script finished.")
104 
105  ## Function to generate graph view of script.
106  #
107  # Starts the script in simulation mode and calls Initialize() and Run().
108  def Parse(self):
109  rospy.loginfo("Start parsing...")
110  global graph
111  # run script in simulation mode
112  self.sss = simple_script_server(parse=True)
113  self.Initialize()
114  self.Run()
115 
116  # save graph on parameter server for further processing
117  #self.graph = graph
118  rospy.set_param("/script_server/graph", graph.string())
119  self.graph_pub.publish(graph.string())
120  rospy.loginfo("...parsing finished")
121  return graph.string()
122 
123 ## Simple script server class.
124 #
125 # Implements the python interface for the script server.
127  ## Initializes simple_script_server class.
128  #
129  # \param parse Defines wether to run script in simulation for graph generation or not
130  def __init__(self, parse=False):
131  global graph
132  self.ns_global_prefix = "/script_server"
133  self.wav_path = ""
134  self.parse = parse
135  try:
136  robot_description = rospy.search_param('robot_description') if rospy.search_param('robot_description') else '/robot_description'
137  rospy.loginfo("Initialize urdf structure from '{}'".format(robot_description))
138  self.robot_urdf = URDF.from_parameter_server(key=robot_description)
139  except KeyError as key_err:
140  self.robot_urdf = None
141  message = "Unable to initialize urdf structure: {}".format(key_err)
142  rospy.logerr(message)
143  rospy.sleep(1) # we have to wait here until publishers are ready, don't ask why
144 
145 #------------------- Init section -------------------#
146  ## Initializes different components.
147  #
148  # Based on the component, the corresponding init service will be called.
149  #
150  # \param component_name Name of the component.
151  def init(self,component_name,blocking=True):
152  return self.trigger(component_name,"init",blocking=blocking)
153 
154  ## Stops different components.
155  #
156  # Based on the component, the corresponding stop service will be called.
157  #
158  # \param component_name Name of the component.
159  def stop(self,component_name,mode="omni",blocking=True):
160  ah = action_handle("stop", component_name, "", False, self.parse)
161  if(self.parse):
162  return ah
163  else:
164  ah.set_active(mode="service")
165 
166  rospy.loginfo("<<stop>> <<%s>>", component_name)
167  if component_name == "base":
168  if(mode == None or mode == ""):
169  action_server_name = "/move_base"
170  elif(mode == "omni"):
171  action_server_name = "/move_base"
172  elif(mode == "diff"):
173  action_server_name = "/move_base_diff"
174  elif(mode == "linear"):
175  action_server_name = "/move_base_linear"
176  else:
177  message = "Given navigation mode " + mode + " for " + component_name + " is not valid, aborting..."
178  rospy.logerr(message)
179  ah.set_failed(33, message)
180  return ah
181  client = actionlib.SimpleActionClient(action_server_name, MoveBaseAction)
182  else:
183  parameter_name = self.ns_global_prefix + "/" + component_name + "/action_name"
184  if not rospy.has_param(parameter_name):
185  message = "Parameter " + parameter_name + " does not exist on ROS Parameter Server, aborting..."
186  rospy.logerr(message)
187  ah.set_failed(2, message)
188  return ah
189  action_server_name = rospy.get_param(parameter_name)
190  client = actionlib.SimpleActionClient(action_server_name, FollowJointTrajectoryAction)
191 
192  # call action server
193  rospy.logdebug("calling %s action server",action_server_name)
194 
195  if blocking:
196  # trying to connect to server
197  rospy.logdebug("waiting for %s action server to start",action_server_name)
198  if not client.wait_for_server(rospy.Duration(1)):
199  # error: server did not respond
200  message = "ActionServer " + action_server_name + " not ready within timeout, aborting..."
201  rospy.logerr(message)
202  ah.set_failed(4, message)
203  return ah
204  else:
205  rospy.logdebug("%s action server ready",action_server_name)
206 
207  # cancel all goals
208  client.cancel_all_goals()
209  ah.set_succeeded() # full success
210  return ah
211 
212  ## Recovers different components.
213  #
214  # Based on the component, the corresponding recover service will be called.
215  #
216  # \param component_name Name of the component.
217  def recover(self,component_name,blocking=True):
218  return self.trigger(component_name,"recover",blocking=blocking)
219 
220  ## Halts different components.
221  #
222  # Based on the component, the corresponding halt service will be called.
223  #
224  # \param component_name Name of the component.
225  def halt(self,component_name,blocking=True):
226  return self.trigger(component_name,"halt",blocking=blocking)
227 
228  ## Deals with all kind of trigger services for different components.
229  #
230  # Based on the component and service name, the corresponding trigger service will be called.
231  #
232  # \param component_name Name of the component.
233  # \param service_name Name of the trigger service.
234  # \param blocking Service calls are always blocking. The parameter is only provided for compatibility with other functions.
235  def trigger(self,component_name,service_name,blocking=True):
236  ah = action_handle(service_name, component_name, "", blocking, self.parse)
237  if(self.parse):
238  return ah
239  else:
240  ah.set_active(mode="service")
241 
242  rospy.loginfo("<<%s>> <<%s>>", service_name, component_name)
243  parameter_name = self.ns_global_prefix + "/" + component_name + "/service_ns"
244  if not rospy.has_param(parameter_name):
245  message = "Parameter " + parameter_name + " does not exist on ROS Parameter Server, aborting..."
246  rospy.logerr(message)
247  ah.set_failed(2, message)
248  return ah
249  service_ns_name = rospy.get_param(parameter_name)
250  service_full_name = service_ns_name + "/" + service_name
251 
252  if blocking:
253  # check if service is available
254  try:
255  rospy.wait_for_service(service_full_name,1)
256  except rospy.ROSException as e:
257  error_message = "%s"%e
258  message = "...service <<" + service_name + ">> of <<" + component_name + ">> not available,\n error: " + error_message
259  rospy.logerr(message)
260  ah.set_failed(4, message)
261  return ah
262 
263  # check if service is callable
264  try:
265  trigger = rospy.ServiceProxy(service_full_name,Trigger)
266  if blocking:
267  rospy.loginfo("Wait for <<%s>> to <<%s>>...", component_name, service_name)
268  resp = trigger()
269  else:
270  Thread(target=trigger).start()
271  except rospy.ServiceException as e:
272  error_message = "%s"%e
273  message = "...calling <<" + service_name + ">> of <<" + component_name + ">> not successfull,\n error: " + error_message
274  rospy.logerr(message)
275  ah.set_failed(10, message)
276  return ah
277 
278  if blocking:
279  # evaluate sevice response
280  if not resp.success:
281  message = "...response of <<" + service_name + ">> of <<" + component_name + ">> not successfull,\n error: " + resp.message
282  rospy.logerr(message)
283  ah.set_failed(10, message)
284  return ah
285 
286  # full success
287  rospy.loginfo("...<<%s>> is <<%s>>", component_name, service_name)
288  ah.set_succeeded() # full success
289  return ah
290 
291  ## Allows to trigger actions of the type actionlib/TestAction
292  #
293  # Based on the component and action name, the corresponding ActionServer will be called.
294  #
295  # \param component_name Name of the component.
296  # \param action_name Name of the action.
297  # \param blocking Whether to wait for the Action to return.
298  def trigger_action(self,component_name,action_name,blocking=True):
299  ah = action_handle(action_name, component_name, "", blocking, self.parse)
300  if(self.parse):
301  return ah
302  else:
303  ah.set_active(mode="action")
304 
305  rospy.loginfo("<<%s>> <<%s>>", action_name, component_name)
306  #parameter_name = self.ns_global_prefix + "/" + component_name + "/service_ns"
307  #if not rospy.has_param(parameter_name):
308  #message = "Parameter " + parameter_name + " does not exist on ROS Parameter Server, aborting..."
309  #rospy.logerr(message)
310  #ah.set_failed(2, message)
311  #return ah
312  #service_ns_name = rospy.get_param(parameter_name)
313  action_full_name = "/" + component_name + "/" + action_name
314  action_client = actionlib.SimpleActionClient(action_full_name, TestAction)
315 
316  if blocking:
317  # check if action is available
318  if not action_client.wait_for_server(rospy.Duration(1)):
319  message = "ActionServer %s is not running"%action_full_name
320  rospy.logerr(message)
321  ah.set_failed(4, message)
322  return ah
323 
324  # call the action
325  if blocking:
326  rospy.loginfo("Wait for <<%s>> to <<%s>>...", component_name, action_name)
327  goal_state = action_client.send_goal_and_wait(TestGoal())
328  if not (action_client.get_state() == GoalStatus.SUCCEEDED):
329  message = "...state of <<" + action_name + ">> of <<" + component_name + ">> : " + GoalStatus.to_string(action_client.get_state())
330  rospy.logerr(message)
331  ah.set_failed(10, message)
332  return ah
333  else:
334  action_client.send_goal(TestGoal())
335 
336  # full success
337  rospy.loginfo("...<<%s>> is <<%s>>", component_name, action_name)
338  ah.set_succeeded() # full success
339  return ah
340 
341 
342  ## Allows to trigger actions of the type cob_actions/SetString
343  #
344  # Based on the component and action name, the corresponding ActionServer will be called.
345  #
346  # \param component_name Name of the component (namespace of the action).
347  # \param data The data to be send in the ActionGoal.
348  # \param blocking Whether to wait for the Action to return.
349  def string_action(self,component_name, data, blocking):
350  action_name = "set_string"
351  ah = action_handle(action_name, component_name, "", blocking, self.parse)
352  if(self.parse):
353  return ah
354  else:
355  ah.set_active(mode="action")
356 
357  rospy.loginfo("<<%s>> <<%s>>", action_name, component_name)
358  action_full_name = "/" + component_name + "/" + action_name
359  action_client = actionlib.SimpleActionClient(action_full_name, SetStringAction)
360 
361  if blocking:
362  # check if action is available
363  if not action_client.wait_for_server(rospy.Duration(1)):
364  message = "ActionServer %s is not running"%action_full_name
365  rospy.logerr(message)
366  ah.set_failed(4, message)
367  return ah
368 
369  # call the action
370  goal = SetStringGoal()
371  goal.data = data
372  if blocking:
373  rospy.loginfo("Wait for <<%s>> to <<%s>>...", component_name, action_name)
374  goal_state = action_client.send_goal_and_wait(goal)
375  if not (action_client.get_state() == GoalStatus.SUCCEEDED):
376  message = "...state of <<" + action_name + ">> of <<" + component_name + ">> : " + GoalStatus.to_string(action_client.get_state())
377  rospy.logerr(message)
378  ah.set_failed(10, message)
379  return ah
380  else:
381  action_client.send_goal(goal)
382 
383  # full success
384  rospy.loginfo("...<<%s>> is <<%s>>", component_name, action_name)
385  ah.set_succeeded() # full success
386  return ah
387 
388 
389 #------------------- Move section -------------------#
390  ## Deals with all kind of movements for different components.
391  #
392  # Based on the component, the corresponding move functions will be called.
393  #
394  # \param component_name Name of the component.
395  # \param parameter_name Name of the parameter on the ROS parameter server.
396  # \param blocking Bool value to specify blocking behaviour.
397  def move(self,component_name,parameter_name,blocking=True, mode=None, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False):
398  if component_name == "base":
399  return self.move_base(component_name,parameter_name,blocking, mode)
400  else:
401  return self.move_traj(component_name,parameter_name,blocking, speed_factor=speed_factor, urdf_vel=urdf_vel, default_vel=default_vel, stop_at_waypoints=stop_at_waypoints)
402 
403  ## Deals with movements of the base.
404  #
405  # A target will be sent to the actionlib interface of the move_base node.
406  #
407  # \param component_name Name of the component.
408  # \param parameter_name Name of the parameter on the ROS parameter server.
409  # \param blocking Bool value to specify blocking behaviour.
410  def move_base(self,component_name,parameter_name,blocking, mode):
411  ah = action_handle("move", component_name, parameter_name, blocking, self.parse)
412  if(self.parse):
413  return ah
414  else:
415  ah.set_active()
416 
417  if(mode == None or mode == ""):
418  rospy.loginfo("Move <<%s>> to <<%s>>",component_name,parameter_name)
419  else:
420  rospy.loginfo("Move <<%s>> to <<%s>> using <<%s>> mode",component_name,parameter_name,mode)
421 
422  # get joint values from parameter server
423  if type(parameter_name) is str:
424  full_parameter_name = self.ns_global_prefix + "/" + component_name + "/" + parameter_name
425  if not rospy.has_param(full_parameter_name):
426  message = "Parameter " + full_parameter_name + " does not exist on ROS Parameter Server, aborting..."
427  rospy.logerr(message)
428  ah.set_failed(2, message)
429  return ah
430  param = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/" + parameter_name)
431  else:
432  param = parameter_name
433 
434  # check trajectory parameters
435  if not type(param) is list: # check outer list
436  message = "No valid parameter for " + component_name + ": not a list, aborting..."
437  rospy.logerr(message)
438  print("parameter is:",param)
439  ah.set_failed(3, message)
440  return ah
441  else:
442  #print i,"type1 = ", type(i)
443  DOF = 3
444  if not len(param) == DOF: # check dimension
445  message = "No valid parameter for " + component_name + ": dimension should be " + str(DOF) + " but is " + str(len(param)) + ", aborting..."
446  rospy.logerr(message)
447  print("parameter is:",param)
448  ah.set_failed(3, message)
449  return ah
450  else:
451  for i in param:
452  #print i,"type2 = ", type(i)
453  if not ((type(i) is float) or (type(i) is int)): # check type
454  #print type(i)
455  message = "No valid parameter for " + component_name + ": not a list of float or int, aborting..."
456  rospy.logerr(message)
457  print("parameter is:",param)
458  ah.set_failed(3, message)
459  return ah
460  else:
461  rospy.logdebug("accepted parameter %f for %s",i,component_name)
462 
463  # convert to pose message
464  pose = PoseStamped()
465  pose.header.stamp = rospy.Time.now()
466  pose.header.frame_id = "map"
467  pose.pose.position.x = param[0]
468  pose.pose.position.y = param[1]
469  pose.pose.position.z = 0.0
470  q = quaternion_from_euler(0, 0, param[2])
471  pose.pose.orientation.x = q[0]
472  pose.pose.orientation.y = q[1]
473  pose.pose.orientation.z = q[2]
474  pose.pose.orientation.w = q[3]
475 
476  # call action server
477  if(mode == None or mode == ""):
478  action_server_name = "/move_base"
479  elif(mode == "omni"):
480  action_server_name = "/move_base"
481  elif(mode == "diff"):
482  action_server_name = "/move_base_diff"
483  elif(mode == "linear"):
484  action_server_name = "/move_base_linear"
485  else:
486  message = "Given navigation mode " + mode + " for " + component_name + " is not valid, aborting..."
487  rospy.logerr(message)
488  ah.set_failed(33, message)
489  return ah
490 
491  rospy.logdebug("calling %s action server",action_server_name)
492  client = actionlib.SimpleActionClient(action_server_name, MoveBaseAction)
493  # trying to connect to server
494  rospy.logdebug("waiting for %s action server to start",action_server_name)
495  if not client.wait_for_server(rospy.Duration(1)):
496  # error: server did not respond
497  message = "ActionServer " + action_server_name + " not ready within timeout, aborting..."
498  rospy.logerr(message)
499  ah.set_failed(4, message)
500  return ah
501  else:
502  rospy.logdebug("%s action server ready",action_server_name)
503 
504  # sending goal
505  client_goal = MoveBaseGoal()
506  client_goal.target_pose = pose
507  #print client_goal
508  client.send_goal(client_goal)
509  ah.set_client(client)
510  ah.wait_inside()
511  return ah
512 
513  def _determine_desired_velocity(self, default_vel, start_pos, component_name, joint_names, speed_factor, urdf_vel):
514  if default_vel: # passed via argument
515  rospy.logdebug("using default_vel from argument")
516  if (type(default_vel) is float) or (type(default_vel) is int):
517  default_vel = numpy.array([default_vel for _ in start_pos])
518  elif (type(default_vel) is list) and (len(default_vel) == len(start_pos)) and all(
519  ((type(item) is float) or (type(item) is int)) for item in default_vel):
520  default_vel = default_vel
521  else:
522  raise ValueError("argument 'default_vel' {} has wrong format (must be float/int or list of float/int) with proper dimensions.".format(default_vel))
523  else: # get from parameter server
524  rospy.logdebug("using default_vel parameter server")
525  param_string = self.ns_global_prefix + "/" + component_name + "/default_vel"
526  if not rospy.has_param(param_string):
527  default_vel = numpy.array([0.1 for _ in start_pos]) # rad/s
528  rospy.logwarn(
529  "parameter '{}' does not exist on ROS Parameter Server, using default_vel {} [rad/sec].".format(
530  param_string, default_vel))
531  else:
532  param_vel = rospy.get_param(param_string)
533  if (type(param_vel) is float) or (type(param_vel) is int):
534  default_vel = numpy.array([param_vel for _ in start_pos])
535  elif (type(param_vel) is list) and (len(param_vel) == len(start_pos)) and all(
536  ((type(item) is float) or (type(item) is int)) for item in param_vel):
537  default_vel = numpy.array(param_vel)
538  else:
539  default_vel = numpy.array([0.1 for _ in start_pos]) # rad/s
540  rospy.logwarn(
541  "parameter '{}' {} has wrong format (must be float/int or list of float/int), using default_vel {} [rad/sec].".format(
542  param_string, param_vel, default_vel))
543  rospy.logdebug("default_vel: {}".format(default_vel))
544 
545  limit_vel = []
546  for idx, joint_name in enumerate(joint_names):
547  try:
548  limit_vel.append(self.robot_urdf.joint_map[joint_name].limit.velocity)
549  except Exception as e:
550  rospy.logwarn("Velocity limits for '{}' could not be retrieved from urdf structure:\n{}\nUsing default velocity: {}".format(joint_name, e, default_vel[idx]))
551  limit_vel.append(default_vel[idx])
552 
553  # limit_vel from urdf or default_vel (from argument or parameter server)
554  if urdf_vel:
555  rospy.logdebug("using default_vel from urdf_limits")
556  velocities = limit_vel
557  else:
558  rospy.logdebug("using default_vel from argument or parameter server")
559  velocities = list(default_vel)
560 
561  # check velocity limits
562  desired_vel = numpy.array(velocities)*speed_factor
563  if (numpy.any(desired_vel > numpy.array(limit_vel))):
564  raise ValueError("desired velocities {} exceed velocity limits {},...aborting".format(desired_vel, numpy.array(limit_vel)))
565 
566  if (numpy.any(desired_vel <= numpy.zeros_like(desired_vel))):
567  raise ValueError("desired velocities {} cannot be zero or negative,...aborting".format(desired_vel))
568  rospy.logdebug("Velocities are: {}".format(desired_vel))
569  return desired_vel
570 
571  ## Parse and compose trajectory message
572  def compose_trajectory(self, component_name, parameter_name, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False):
573  if urdf_vel and default_vel:
574  rospy.logerr("arguments not valid - cannot set 'urdf_vel' and 'default_vel' at the same time, aborting...")
575  return (JointTrajectory(), 3)
576 
577  # get joint_names from parameter server
578  param_string = self.ns_global_prefix + "/" + component_name + "/joint_names"
579  if not rospy.has_param(param_string):
580  rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",param_string)
581  return (JointTrajectory(), 2)
582  joint_names = rospy.get_param(param_string)
583 
584  # check joint_names parameter
585  if not type(joint_names) is list: # check list
586  rospy.logerr("no valid joint_names for %s: not a list, aborting...",component_name)
587  print("joint_names are:",joint_names)
588  return (JointTrajectory(), 3)
589  else:
590  for i in joint_names:
591  #print i,"type1 = ", type(i)
592  if not type(i) is str: # check string
593  rospy.logerr("no valid joint_names for %s: not a list of strings, aborting...",component_name)
594  print("joint_names are:", joint_names)
595  return (JointTrajectory(), 3)
596  else:
597  rospy.logdebug("accepted joint_names for component %s",component_name)
598 
599  # get joint values from parameter server
600  if type(parameter_name) is str:
601  full_parameter_name = self.ns_global_prefix + "/" + component_name + "/" + parameter_name
602  if not rospy.has_param(full_parameter_name):
603  rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",full_parameter_name)
604  return (JointTrajectory(), 2)
605  param = rospy.get_param(full_parameter_name)
606  else:
607  param = parameter_name
608 
609  # check trajectory parameters
610  if not type(param) is list: # check outer list
611  rospy.logerr("no valid parameter for %s: not a list, aborting...",component_name)
612  print("parameter is:",param)
613  return (JointTrajectory(), 3)
614 
615  traj = []
616  for point in param:
617  #print point,"type1 = ", type(point)
618  if type(point) is str:
619  full_parameter_name = self.ns_global_prefix + "/" + component_name + "/" + point
620  if not rospy.has_param(full_parameter_name):
621  rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",full_parameter_name)
622  return (JointTrajectory(), 2)
623  point = rospy.get_param(full_parameter_name)
624  point = point[0] # \todo TODO: hack because only first point is used, no support for trajectories inside trajectories
625  #print point
626  elif type(point) is list:
627  rospy.logdebug("point is a list")
628  else:
629  rospy.logerr("no valid parameter for %s: not a list of lists or strings, aborting...",component_name)
630  print("parameter is:",param)
631  return (JointTrajectory(), 3)
632 
633  # here: point should be list of floats/ints
634  #print point
635  if not len(point) == len(joint_names): # check dimension
636  rospy.logerr("no valid parameter for %s: dimension should be %d and is %d, aborting...",component_name,len(joint_names),len(point))
637  print("parameter is:",param)
638  return (JointTrajectory(), 3)
639 
640  for value in point:
641  #print value,"type2 = ", type(value)
642  if not ((type(value) is float) or (type(value) is int)): # check type
643  #print type(value)
644  rospy.logerr("no valid parameter for %s: not a list of float or int, aborting...",component_name)
645  print("parameter is:",param)
646  return (JointTrajectory(), 3)
647 
648  rospy.logdebug("accepted value %f for %s",value,component_name)
649  traj.append(point)
650 
651  rospy.logdebug("accepted trajectory for %s",component_name)
652  rospy.logdebug("traj after param: {}".format(traj))
653 
654  # get current pos
655  timeout = 3.0
656  try:
657  joint_state_topic = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/joint_state_topic", "/" + component_name + "/joint_states")
658  joint_state_message = rospy.wait_for_message(joint_state_topic, JointState, timeout = timeout) # type: JointState
659  # make sure we have the same joint order
660  start_pos = []
661  for name in joint_names:
662  idx = joint_state_message.name.index(name)
663  start_pos.append(joint_state_message.position[idx])
664  except rospy.ROSException as e:
665  rospy.logwarn("no joint states received from %s within timeout of %ssec. using default point time of 8sec.", component_name, str(timeout))
666  start_pos = []
667 
668  # insert start_pos to trajectory
669  if start_pos:
670  traj.insert(0,start_pos)
671  rospy.logdebug("traj after add: {}".format(traj))
672 
673  # convert to ROS trajectory message
674  traj_msg = JointTrajectory()
675  # if no timestamp is set in header, this means that the trajectory starts "now"
676  traj_msg.joint_names = joint_names
677  point_nr = 0
678  traj_time = 0
679 
680  # get desired_vel
681  try:
682  desired_vel = self._determine_desired_velocity(default_vel, start_pos, component_name, joint_names, speed_factor, urdf_vel)
683  except ValueError as val_err:
684  rospy.logerr(val_err)
685  return (JointTrajectory(), 3)
686 
687  # get default_acc
688  param_string = self.ns_global_prefix + "/" + component_name + "/default_acc"
689  if not rospy.has_param(param_string):
690  default_acc = numpy.array([1.0 for _ in start_pos]) # rad^2/s
691  rospy.logwarn("parameter '{}' does not exist on ROS Parameter Server, using default_acc {} [rad^2/sec].".format(param_string,default_acc))
692  else:
693  param_acc = rospy.get_param(param_string)
694  if (type(param_acc) is float) or (type(param_acc) is int):
695  default_acc = numpy.array([param_acc for _ in start_pos])
696  elif (type(param_acc) is list) and (len(param_acc) == len(start_pos)) and all(
697  ((type(item) is float) or (type(item) is int)) for item in param_acc):
698  default_acc = numpy.array(param_acc)
699  else:
700  default_acc = numpy.array([1.0 for _ in start_pos]) # rad^2/s
701  rospy.logwarn("parameter '{}' {} has wrong format (must be float/int or list of float/int), using default_acc {} [rad^2/sec].".format(param_string,param_acc,default_acc))
702 
703  # filter duplicates
704  def is_close(a,b):
705  return numpy.all(numpy.isclose(numpy.array(a), numpy.array(b), atol=0.001))
706 
707  def unique_next(elems):
708  for i, (curr, nxt) in enumerate(zip(elems, elems[1:]+[None])):
709  if not nxt:
710  yield curr
711  else:
712  if not is_close(curr, nxt):
713  yield curr
714  else:
715  rospy.logdebug("dropping trajectory point {} due to is close: (curr {}, nxt: {})".format(i, curr, nxt))
716 
717  try:
718  traj = list(unique_next(traj))
719  except Exception as e:
720  rospy.logerr(e)
721  return (JointTrajectory(), 3)
722  rospy.logdebug("traj after unique_nxt: {}".format(traj))
723 
724  # calculate time_from_start
725  for point in traj:
726  point_nr = point_nr + 1
727  point_msg = JointTrajectoryPoint()
728  point_msg.positions = point
729 
730  # use hardcoded point_time if no start_pos available
731  if start_pos != []:
732  point_time = self.calculate_point_time(start_pos, point, desired_vel, default_acc)
733  else:
734  point_time = 8*point_nr
735 
736  start_pos = point
737  point_msg.time_from_start=rospy.Duration(point_time + traj_time)
738  traj_time += point_time
739  traj_msg.points.append(point_msg)
740 
741  # calculate traj_point velocities and accelerations
742  prevs, items, nexts = itertools.tee(traj_msg.points, 3)
743  prevs = itertools.chain([None], prevs)
744  nexts = itertools.chain(itertools.islice(nexts, 1, None), [None])
745  for idx, (pre, curr, post) in enumerate(zip(prevs, items, nexts)):
746  traj_msg.points[idx].velocities = self.calculate_point_velocities(pre, curr, post, stop_at_waypoints)
747  traj_msg.points[idx].accelerations = self.calculate_point_accelerations(pre, curr, post)
748 
749  # drop first trajectory point because it is equal to start_pos
750  traj_msg.points = traj_msg.points[1:]
751 
752  return (traj_msg, 0)
753 
754  def calculate_point_time(self, start_pos, end_pos, default_vel, default_acc):
755  if isinstance(default_vel, float):
756  default_vel = numpy.array([default_vel for _ in start_pos])
757 
758  if isinstance(default_acc, float):
759  default_acc = numpy.array([default_acc for _ in start_pos])
760 
761  try:
762  # dist: Distance traveled in the move by each joint
763  dist = numpy.abs(numpy.array(start_pos) - numpy.array(end_pos))
764 
765  t1 = default_vel / default_acc # Time needed for joints to accelerate to desired velocity
766  s1 = default_acc / 2.0 * t1**2 # Distance traveled during this time
767 
768  t = numpy.zeros_like(dist)
769 
770  for i in range(len(start_pos)):
771  if 2 * s1[i] < dist[i]:
772  # If we can accelerate and decelerate in less than the total distance, then:
773  # accelerate up to speed, travel at that speed for a bit and then decelerate, a three phase trajectory:
774  # with constant velocity phase (acc, const vel, dec)
775  # 1st phase: accelerate from v=0 to v=default_vel with a=default_acc in t=t1. Need s1 distance for this
776  # 2nd phase: constant velocity with v=default_vel and t=t2
777  # 3rd phase: deceleration (analog to 1st phase). Need s1 distance for this
778  # ^
779  # | __2__
780  # | / \
781  # v|1 / \ 3
782  # | / \
783  # o--------------->
784  # t d_max
785  s2 = dist[i] - 2 * s1[i]
786  t2 = s2 / default_vel[i]
787  t[i] = 2 * t1[i] + t2
788  else:
789  # If we don't have enough distance to get to full speed, then we do
790  # without constant velocity phase (only acc and dec, so a two phase trajectory)
791  # 1st phase: accelerate from v=0 to v=default_vel with a=default_acc in t=t1
792  # 2nd phase: missing because distance is to short (we already reached the distance with the acc and dec phase)
793  # 3rd phase: deceleration (analog to 1st phase)
794  t[i] = numpy.sqrt(dist[i] / default_acc[i])
795 
796  # Instead of deciding per joint if we can do a three or two-phase trajectory,
797  # we can simply take the slowest joint of them all and select that.
798  #point_time = max(numpy.max(t), 0.4) # use minimal point_time
799  point_time = numpy.max(t)
800  except ValueError as e:
801  print("Value Error: {}".format(e))
802  print("Likely due to mimic joints. Using default point_time: 3.0 [sec]")
803  point_time = 3.0 # use default point_time
804  return point_time
805 
806  def calculate_point_velocities(self, prev, curr, post, stop_at_waypoints=False):
807  rospy.logdebug("calculate_point_velocities")
808  rospy.logdebug("prev: {}".format(prev))
809  rospy.logdebug("curr: {}".format(curr))
810  rospy.logdebug("post: {}".format(post))
811 
812  if stop_at_waypoints:
813  rospy.logdebug("stop_at_waypoints")
814  point_velocities = numpy.zeros(len(curr.positions))
815  elif not post: # set zero velocities for last trajectory point only
816  rospy.logdebug("not has post")
817  point_velocities = numpy.zeros(len(curr.positions))
818  elif not prev:
819  rospy.logdebug("not has prev")
820  point_velocities = numpy.zeros(len(curr.positions))
821  else:
822  rospy.logdebug("has prev, has post")
823  # calculate based on difference quotient post-curr
824  point_velocities = numpy.divide(numpy.subtract(numpy.array(post.positions), numpy.array(prev.positions)), numpy.array([(post.time_from_start-prev.time_from_start).to_sec()]*len(curr.positions)))
825  rospy.logdebug("point_velocities diff quot: {}".format(point_velocities))
826 
827  # check sign change or consecutive points too close
828  rospy.logdebug("has prev")
829  curr_prev_diff = numpy.subtract(numpy.array(curr.positions), numpy.array(prev.positions))
830  post_curr_diff = numpy.subtract(numpy.array(post.positions), numpy.array(curr.positions))
831  rospy.logdebug("curr_prev_diff: {}".format(curr_prev_diff))
832  rospy.logdebug("post_curr_diff: {}".format(post_curr_diff))
833  same_sign = numpy.equal(numpy.sign(curr_prev_diff), numpy.sign(post_curr_diff))
834  prev_close = numpy.isclose(curr_prev_diff, numpy.zeros_like(curr_prev_diff), atol=0.01)
835  post_close = numpy.isclose(post_curr_diff, numpy.zeros_like(post_curr_diff), atol=0.01)
836  rospy.logdebug("same_sign: {}".format(same_sign))
837  rospy.logdebug("prev_close: {}".format(prev_close))
838  rospy.logdebug("post_close: {}".format(post_close))
839 
840  for idx, vel in enumerate(point_velocities):
841  if prev_close[idx]:
842  rospy.logdebug("prev close for joint {} - setting vel to 0.0".format(idx))
843  point_velocities[idx] = 0.0
844  if post_close[idx]:
845  rospy.logdebug("post close for joint {} - setting vel to 0.0".format(idx))
846  point_velocities[idx] = 0.0
847  if not same_sign[idx]:
848  rospy.logdebug("sign change for joint {} - setting vel to 0.0".format(idx))
849  point_velocities[idx] = 0.0
850 
851  rospy.logdebug("point_velocities: {}".format(point_velocities))
852  return list(point_velocities)
853 
854  def calculate_point_accelerations(self, prev, curr, post):
855  return [0]*len(curr.positions)
856 
857  ## Deals with all kind of trajectory movements for different components.
858  #
859  # A trajectory will be sent to the actionlib interface of the corresponding component.
860  #
861  # \param component_name Name of the component.
862  # \param parameter_name Name of the parameter on the ROS parameter server.
863  # \param blocking Bool value to specify blocking behaviour.
864  def move_traj(self,component_name,parameter_name,blocking, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False):
865  ah = action_handle("move", component_name, parameter_name, blocking, self.parse)
866  if(self.parse):
867  return ah
868  else:
869  ah.set_active()
870 
871  rospy.loginfo("Move <<%s>> to <<%s>>",component_name,parameter_name)
872  (traj_msg, error_code) = self.compose_trajectory(component_name, parameter_name, speed_factor=speed_factor, urdf_vel=urdf_vel, default_vel=default_vel, stop_at_waypoints=stop_at_waypoints)
873  if error_code != 0:
874  message = "Composing the trajectory failed with error: " + str(error_code)
875  ah.set_failed(error_code, message)
876  return ah
877 
878  # call action server
879  parameter_name = self.ns_global_prefix + "/" + component_name + "/action_name"
880  if not rospy.has_param(parameter_name):
881  message = "Parameter " + parameter_name + " does not exist on ROS Parameter Server, aborting..."
882  rospy.logerr(message)
883  ah.set_failed(2, message)
884  return ah
885  action_server_name = rospy.get_param(parameter_name)
886  rospy.logdebug("calling %s action server",action_server_name)
887  client = actionlib.SimpleActionClient(action_server_name, FollowJointTrajectoryAction)
888  # trying to connect to server
889  rospy.logdebug("waiting for %s action server to start",action_server_name)
890  if not client.wait_for_server(rospy.Duration(1)):
891  # error: server did not respond
892  message = "ActionServer " + action_server_name + " not ready within timeout, aborting..."
893  rospy.logerr(message)
894  ah.set_failed(4, message)
895  return ah
896  else:
897  rospy.logdebug("%s action server ready",action_server_name)
898 
899  # sending goal
900  client_goal = FollowJointTrajectoryGoal()
901  client_goal.trajectory = traj_msg
902  #print client_goal
903  client.send_goal(client_goal)
904  ah.set_client(client)
905  ah.wait_inside()
906  return ah
907 
908  ## Relative movement of the base
909  #
910  # \param component_name Name of component; here always "base".
911  # \param parameter_name List of length 3: (item 1 & 2) relative x and y translation [m]; (item 3) relative rotation about z axis [rad].
912  # \param blocking Bool value to specify blocking behaviour.
913  #
914  # # throws error code 3 in case of invalid parameter_name vector
915  def move_base_rel(self, component_name, parameter_name=[0,0,0], blocking=True):
916  ah = action_handle("move_base_rel", component_name, parameter_name, blocking, self.parse)
917  if(self.parse):
918  return ah
919  else:
920  ah.set_active(mode="topic")
921 
922  parameter_topic_name = self.ns_global_prefix + "/" + component_name + "/topic_name"
923  if not rospy.has_param(parameter_topic_name):
924  message = "Parameter " + parameter_topic_name + " does not exist on ROS Parameter Server, aborting..."
925  rospy.logerr(message)
926  ah.set_failed(3, message)
927  return ah
928  topic_name = rospy.get_param(parameter_topic_name)
929  rospy.loginfo("Move base relatively by <<%s>>", parameter_name)
930 
931  # step 0: check validity of parameters:
932  if not len(parameter_name) == 3 or not isinstance(parameter_name[0], (int, float)) or not isinstance(parameter_name[1], (int, float)) or not isinstance(parameter_name[2], (int, float)):
933  message = "Parameter " + parameter_name + " not formated correctly (non-numeric list), aborting move_base_rel"
934  rospy.logerr(message)
935  print("parameter_name must be numeric list of length 3; (relative x and y transl [m], relative rotation [rad])")
936  ah.set_failed(3, message)
937  return ah
938  max_rel_trans_step = 1.0 # [m]
939  max_rel_rot_step = math.pi/2 # [rad]
940  if math.sqrt(parameter_name[0]**2 + parameter_name[1]**2) > max_rel_trans_step:
941  message = "Parameter " + str(parameter_name) + " exceeds maximal relative translation step (" + str(max_rel_trans_step) + "), aborting move_base_rel"
942  rospy.logerr(message)
943  ah.set_failed(3, message)
944  return(ah)
945  if abs(parameter_name[2]) > max_rel_rot_step:
946  message = "Parameter " + str(parameter_name) + " exceeds maximal relative rotation step (" + str(max_rel_rot_step) + "), aborting move_base_rel"
947  rospy.logerr(message)
948  ah.set_failed(3, message)
949  return(ah)
950 
951  # step 1: determine duration of motion so that upper thresholds for both translational as well as rotational velocity are not exceeded
952  max_trans_vel = 0.05 # [m/s]
953  max_rot_vel = 0.2 # [rad/s]
954  duration_trans_sec = math.sqrt(parameter_name[0]**2 + parameter_name[1]**2) / max_trans_vel
955  duration_rot_sec = abs(parameter_name[2] / max_rot_vel)
956  duration_sec = max(duration_trans_sec, duration_rot_sec)
957  duration_ros = rospy.Duration.from_sec(duration_sec) # duration of motion in ROS time
958 
959  # step 2: determine actual velocities based on calculated duration
960  x_vel = parameter_name[0] / duration_sec
961  y_vel = parameter_name[1] / duration_sec
962  rot_vel = parameter_name[2] / duration_sec
963 
964  # step 3: send constant velocity command to base_controller for the calculated duration of motion
965  pub = rospy.Publisher(topic_name, Twist, queue_size=1)
966  twist = Twist()
967  twist.linear.x = x_vel
968  twist.linear.y = y_vel
969  twist.angular.z = rot_vel
970  end_time = rospy.Time.now() + duration_ros
971 
972  if blocking:
973  rospy.loginfo("Wait for <<%s>> to finish move_base_rel...", component_name)
974  self.publish_twist(pub, twist, end_time)
975  else:
976  Thread(target=self.publish_twist, args=(pub, twist, end_time)).start()
977 
978  ah.set_succeeded()
979  return ah
980 
981  def publish_twist(self, pub, twist, end_time):
982  r = rospy.Rate(10) # send velocity commands at 10 Hz
983  while not rospy.is_shutdown() and rospy.Time.now() < end_time:
984  pub.publish(twist)
985  r.sleep()
986 
987  ## Relative movement
988  ## Deals with all kind of relative movements for different components.
989  #
990  # Based on the component, the corresponding move functions will be called.
991  #
992  # \param component_name Name of the component.
993  # \param parameter_name List of movements for each joint of the component
994  # \param blocking Bool value to specify blocking behaviour.
995  #
996  # # throws error code 3 in case of invalid parameter_name vector
997  def move_rel(self, component_name, parameter_name, blocking=True, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False):
998  ah = action_handle("move_rel", component_name, parameter_name, blocking, self.parse)
999  if(self.parse):
1000  return ah
1001  else:
1002  ah.set_active(mode="topic")
1003 
1004  rospy.loginfo("Move <<%s>> relatively by <<%s>>", component_name, parameter_name)
1005 
1006  # get joint_names from parameter server
1007  param_string = self.ns_global_prefix + "/" + component_name + "/joint_names"
1008  if not rospy.has_param(param_string):
1009  message = "parameter " + str(param_string) + " does not exist on ROS Parameter Server, aborting move_rel"
1010  rospy.logerr(message)
1011  ah.set_failed(3, message)
1012  return ah
1013  joint_names = rospy.get_param(param_string)
1014 
1015  # check joint_names parameter
1016  if not type(joint_names) is list: # check list
1017  message = "no valid joint_names for " + str(component_name) + ": not a list, aborting move_rel"
1018  rospy.logerr(message)
1019  print("joint_names are:",joint_names)
1020  ah.set_failed(3, message)
1021  return ah
1022  else:
1023  for i in joint_names:
1024  #print i,"type1 = ", type(i)
1025  if not type(i) is str: # check string
1026  message = "no valid joint_names for " + str(component_name) + ": not a list of strings, aborting move_rel"
1027  rospy.logerr(message)
1028  print("joint_names are:", joint_names)
1029  ah.set_failed(3, message)
1030  return ah
1031  else:
1032  rospy.logdebug("accepted joint_names for component %s",component_name)
1033 
1034  # step 0: check validity of parameters:
1035  if not isinstance(parameter_name, list):
1036  message = "Parameter " + str(parameter_name) + " not formated correctly (not a list), aborting move_rel"
1037  rospy.logerr(message)
1038  ah.set_failed(3, message)
1039  return ah
1040  for parameter in parameter_name:
1041  if not isinstance(parameter, list):
1042  message = "Parameter " + str(parameter_name) + " not formated correctly (not a list of lists), aborting move_rel"
1043  rospy.logerr(message)
1044  ah.set_failed(3, message)
1045  return ah
1046  for param in parameter:
1047  if not isinstance(param, (int, float)):
1048  message = "Parameter " + str(parameter) + " not formated correctly (not a list of numeric lists), aborting move_rel"
1049  rospy.logerr(message)
1050  ah.set_failed(3, message)
1051  return ah
1052 
1053  # step 1: get current position
1054  timeout = 1.0
1055  try:
1056  joint_state_topic = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/joint_state_topic", "/" + component_name + "/joint_states")
1057  joint_state_message = rospy.wait_for_message(joint_state_topic, JointState, timeout = timeout) # type: JointState
1058  # make sure we have the same joint order
1059  start_pos = []
1060  for name in joint_names:
1061  idx = joint_state_message.name.index(name)
1062  start_pos.append(joint_state_message.position[idx])
1063  except rospy.ROSException:
1064  message = "no joint states received from %s within timeout of %ssec."%(component_name, str(timeout))
1065  rospy.logerr(message)
1066  ah.set_failed(3, message)
1067  return ah
1068 
1069  # step 2: get joint limits from urdf
1070  if not self.robot_urdf:
1071  message = "Failed to get joint limits from urdf structure - urdf structure is not initialized"
1072  rospy.logerr(message)
1073  ah.set_failed(3, message)
1074  return ah
1075  limits = {}
1076  for joint in self.robot_urdf.joints:
1077  limits.update({joint.name : joint.limit})
1078 
1079  # step 3 calculate and send goal
1080  end_poses = []
1081  for move_rel_param in parameter_name:
1082  end_pos = []
1083  if len(start_pos) == len(move_rel_param) and len(joint_names) == len(move_rel_param):
1084  for i in range(len(joint_names)):
1085  if (end_poses == []):
1086  pos_val = start_pos[i] + move_rel_param[i]
1087  # for multiple movements, append move_rel_param to previous calculated pose
1088  else:
1089  pos_val = end_poses[-1][i] + move_rel_param[i]
1090  # check if joint limits are exceeded
1091  if limits[joint_names[i]].upper > pos_val and limits[joint_names[i]].lower < pos_val:
1092  end_pos.append(pos_val)
1093  else:
1094  message = "Relative motion wil exceed absolute limits! %s would go to %f but limits are: %f (upper) and %f (lower)"%(joint_names[i], pos_val, limits[joint_names[i]].upper, limits[joint_names[i]].lower)
1095  rospy.logerr(message)
1096  ah.set_failed(3, message)
1097  return ah
1098  else:
1099  message = "Parameters %s don't fit with joint states!"%str(move_rel_param)
1100  rospy.logerr(message)
1101  ah.set_failed(3, message)
1102  return ah
1103  end_poses.append(end_pos)
1104 
1105  return self.move_traj(component_name, end_poses, blocking, speed_factor=speed_factor, urdf_vel=urdf_vel, default_vel=default_vel, stop_at_waypoints=stop_at_waypoints)
1106 
1107 #------------------- LED section -------------------#
1108  ## Set the color of the cob_light component.
1109  #
1110  # The color is given by a parameter on the parameter server.
1111  #
1112  # \param parameter_name Name of the parameter on the parameter server which holds the rgb values.
1113 
1114  def compose_color(self,component_name,parameter_name):
1115  # get joint values from parameter server
1116  if type(parameter_name) is str:
1117  full_parameter_name = self.ns_global_prefix + "/" + component_name + "/" + parameter_name
1118  if not rospy.has_param(full_parameter_name):
1119  rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",full_parameter_name)
1120  return 2, None
1121  param = rospy.get_param(full_parameter_name)
1122  else:
1123  param = parameter_name
1124 
1125  # check color parameters
1126  if not type(param) is list: # check outer list
1127  rospy.logerr("no valid parameter for light: not a list, aborting...")
1128  print("parameter is:",param)
1129  return 3, None
1130  else:
1131  if not len(param) == 4: # check dimension
1132  rospy.logerr("no valid parameter for light: dimension should be 4 (r,g,b,a) and is %d, aborting...",len(param))
1133  print("parameter is:",param)
1134  return 3, None
1135  else:
1136  for i in param:
1137  #print i,"type1 = ", type(i)
1138  if not ((type(i) is float) or (type(i) is int)): # check type
1139  #print type(i)
1140  rospy.logerr("no valid parameter for light: not a list of float or int, aborting...")
1141  print("parameter is:",param)
1142  return 3, None
1143  else:
1144  rospy.logdebug("accepted parameter %f for light",i)
1145 
1146  # convert to ColorRGBA message
1147  color = ColorRGBA()
1148  color.r = param[0]
1149  color.g = param[1]
1150  color.b = param[2]
1151  color.a = param[3] # Transparency
1152  return 0, color
1153 
1154  def set_light(self,component_name,parameter_name,blocking=False):
1155  ah = action_handle("set_light", component_name, parameter_name, blocking, self.parse)
1156  if(self.parse):
1157  return ah
1158  else:
1159  ah.set_active()
1160  rospy.loginfo("Set <<%s>> to <<%s>>", component_name, parameter_name)
1161 
1162  mode = LightMode()
1163  mode.mode = LightModes.STATIC
1164  color = ColorRGBA()
1165  (error,color) = self.compose_color(component_name, parameter_name)
1166  if error != 0:
1167  message = "Composing the color failed with error: " + str(error)
1168  ah.set_failed(error, message)
1169  return ah
1170  mode.colors = []
1171  mode.colors.append(color)
1172 
1173  # call action server
1174  action_server_name = component_name + "/set_light"
1175  rospy.logdebug("calling %s action server",action_server_name)
1176  client = actionlib.SimpleActionClient(action_server_name, SetLightModeAction)
1177  # trying to connect to server
1178  rospy.logdebug("waiting for %s action server to start",action_server_name)
1179  if not client.wait_for_server(rospy.Duration(1)):
1180  # error: server did not respond
1181  message = "ActionServer " + action_server_name + " not ready within timeout, aborting..."
1182  rospy.logerr(message)
1183  ah.set_failed(4, message)
1184  return ah
1185  else:
1186  rospy.logdebug("%s action server ready",action_server_name)
1187 
1188  # sending goal
1189  goal = SetLightModeGoal()
1190  goal.mode = mode
1191  client.send_goal(goal)
1192  ah.set_client(client)
1193  ah.wait_inside()
1194  return ah
1195 
1196 #------------------- Mimic section -------------------#
1197  ## Set the mimic of the cob_mimic component.
1198  #
1199  # The mode is given by a parameter on the parameter server.
1200  #
1201  # \param parameter_name Name of the parameter on the parameter server which holds the mimic mode (string).
1202 
1203  def set_mimic(self,component_name,parameter_name,blocking=False):
1204  ah = action_handle("set_mimic", component_name, parameter_name, blocking, self.parse)
1205  if(self.parse):
1206  return ah
1207  else:
1208  ah.set_active()
1209  rospy.loginfo("Set <<%s>> to <<%s>>", component_name, parameter_name)
1210 
1211  # check mimic parameters
1212  mimic = SetMimicGoal()
1213  if not (type(parameter_name) is str or type(parameter_name) is list): # check outer list
1214  message = "No valid parameter for mimic: not a string or list, aborting..."
1215  rospy.logerr(message)
1216  print("parameter is:",parameter_name)
1217  ah.set_failed(3, message)
1218  return ah
1219 
1220  if type(parameter_name) is str:
1221  mimic.mimic = parameter_name
1222  elif type(parameter_name) is list:
1223  if len(parameter_name) != 3:
1224  message = "No valid parameter for mimic: not a list with size 3, aborting..."
1225  rospy.logerr(message)
1226  print("parameter is:",parameter_name)
1227  ah.set_failed(3, message)
1228  return ah
1229  if ((type(parameter_name[0]) is str) and (type(parameter_name[1]) is float or type(parameter_name[1]) is int) and (type(parameter_name[2]) is float or type(parameter_name[2]) is int)):
1230  mimic.mimic = parameter_name[0]
1231  mimic.speed = parameter_name[1]
1232  mimic.repeat = parameter_name[2]
1233  else:
1234  message = "No valid parameter for mimic: not a list with [mode, speed, repeat], aborting..."
1235  rospy.logerr(message)
1236  print("parameter is:",parameter_name)
1237  ah.set_failed(3, message)
1238  return ah
1239  else:
1240  rospy.logerr("you should never be here")
1241  rospy.logdebug("accepted parameter %s for mimic",parameter_name)
1242 
1243  # call action server
1244  action_server_name = component_name + "/set_mimic"
1245  rospy.logdebug("calling %s action server",action_server_name)
1246  client = actionlib.SimpleActionClient(action_server_name, SetMimicAction)
1247  # trying to connect to server
1248  rospy.logdebug("waiting for %s action server to start",action_server_name)
1249  if not client.wait_for_server(rospy.Duration(1)):
1250  # error: server did not respond
1251  message = "ActionServer " + action_server_name + " not ready within timeout, aborting..."
1252  rospy.logerr(message)
1253  ah.set_failed(4, message)
1254  return ah
1255  else:
1256  rospy.logdebug("%s action server ready",action_server_name)
1257 
1258  # sending goal
1259  client.send_goal(mimic)
1260  ah.set_client(client)
1261  ah.wait_inside()
1262  return ah
1263 
1264 #-------------------- Sound section --------------------#
1265  ## Say some text.
1266  #
1267  # The text to say may be given by a list of strings or a single string which points to a parameter on the ROS parameter server.
1268  #
1269  # \param parameter_name Name of the parameter
1270  # \param language Language to use for the TTS system
1271  def say(self,component_name,parameter_name,blocking=True):
1272  ah = action_handle("say", component_name, parameter_name, blocking, self.parse)
1273  if(self.parse):
1274  return ah
1275  else:
1276  ah.set_active()
1277 
1278  text = ""
1279  # get values from parameter server
1280  language = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/language","en")
1281  if type(parameter_name) is str:
1282  full_parameter_name = self.ns_global_prefix + "/" + component_name + "/" + language + "/" + parameter_name
1283  if not rospy.has_param(full_parameter_name):
1284  message = "Parameter " + full_parameter_name + " does not exist on ROS Parameter Server, aborting..."
1285  rospy.logerr(message)
1286  ah.set_failed(2, message)
1287  return ah
1288  param = rospy.get_param(full_parameter_name)
1289  else:
1290  param = parameter_name
1291 
1292  # check parameters
1293  if not type(param) is list: # check list
1294  message = "No valid parameter for " + component_name + ": not a list, aborting..."
1295  rospy.logerr(message)
1296  print("parameter is:",param)
1297  ah.set_failed(3, message)
1298  return ah
1299  else:
1300  for i in param:
1301  #print i,"type1 = ", type(i)
1302  if not type(i) is str:
1303  message = "No valid parameter for " + component_name + ": not a list of strings, aborting..."
1304  rospy.logerr(message)
1305  print("parameter is:",param)
1306  ah.set_failed(3, message)
1307  return ah
1308  else:
1309  text = text + i + " "
1310  rospy.logdebug("accepted parameter <<%s>> for <<%s>>",i,component_name)
1311  rospy.loginfo("Saying <<%s>>",text)
1312 
1313  # call action server
1314  action_server_name = component_name + "/say"
1315  rospy.logdebug("calling %s action server",action_server_name)
1316  client = actionlib.SimpleActionClient(action_server_name, SayAction)
1317  # trying to connect to server
1318  rospy.logdebug("waiting for %s action server to start",action_server_name)
1319  if not client.wait_for_server(rospy.Duration(1)):
1320  # error: server did not respond
1321  message = "ActionServer " + action_server_name + " not ready within timeout, aborting..."
1322  rospy.logerr(message)
1323  ah.set_failed(4, message)
1324  return ah
1325  else:
1326  rospy.logdebug("%s action server ready",action_server_name)
1327 
1328  # sending goal
1329  client_goal = SayGoal()
1330  client_goal.text = text
1331  #print client_goal
1332  client.send_goal(client_goal)
1333  ah.set_client(client)
1334  ah.wait_inside()
1335  return ah
1336 
1337  ## Play a sound file.
1338  #
1339  # \param parameter_name Name of the parameter
1340  # \param language Language to use
1341  def play(self,component_name, parameter_name,blocking=True):
1342  ah = action_handle("play", component_name, parameter_name, False, self.parse)
1343  if(self.parse):
1344  return ah
1345  else:
1346  ah.set_active()
1347 
1348  if not (type(parameter_name) is str or type(parameter_name) is list): # check outer list
1349  message = "No valid parameter for play: not a string or list, aborting..."
1350  rospy.logerr(message)
1351  print("parameter is:",parameter_name)
1352  ah.set_failed(3, message)
1353  return ah
1354 
1355  if type(parameter_name) is str:
1356  full_parameter_name = self.ns_global_prefix + "/" + component_name + "/" + "audio_file_path"
1357  if not rospy.has_param(full_parameter_name):
1358  message = "Parameter " + full_parameter_name + " does not exist on ROS Parameter Server, aborting..."
1359  rospy.logerr(message)
1360  ah.set_failed(2, message)
1361  return ah
1362  filename = rospy.get_param(full_parameter_name) + "/" + parameter_name + ".wav"
1363  elif type(parameter_name) is list:
1364  if len(parameter_name) != 3:
1365  message = "No valid parameter for play: not a list with size 3, aborting..."
1366  rospy.logerr(message)
1367  print("parameter is:",parameter_name)
1368  ah.set_failed(3, message)
1369  return ah
1370  if ((type(parameter_name[0]) is str) and (type(parameter_name[1]) is str) and (type(parameter_name[2]) is str)):
1371  filename = parameter_name[1] + "/" + parameter_name[0] + "." + parameter_name[2]
1372  else:
1373  message = "No valid parameter for play: not a list with [filename, file_path, file_suffix], aborting..."
1374  rospy.logerr(message)
1375  print("parameter is:",parameter_name)
1376  ah.set_failed(3, message)
1377  return ah
1378  else:
1379  rospy.logerr("you should never be here")
1380  rospy.logdebug("accepted parameter %s for play",parameter_name)
1381 
1382  action_server_name = component_name + "/play"
1383  rospy.logdebug("calling %s action server",action_server_name)
1384  client = actionlib.SimpleActionClient(action_server_name, PlayAction)
1385  # trying to connect to server
1386  rospy.logdebug("waiting for %s action server to start",action_server_name)
1387  if not client.wait_for_server(rospy.Duration(1)):
1388  # error: server did not respond
1389  message = "ActionServer " + action_server_name + " not ready within timeout, aborting..."
1390  rospy.logerr(message)
1391  ah.set_failed(4, message)
1392  return ah
1393  else:
1394  rospy.logdebug("%s action server ready",action_server_name)
1395 
1396  # sending goal
1397  rospy.loginfo("Playing <<%s>>",filename)
1398  client_goal = PlayGoal()
1399  client_goal.filename = filename
1400  #print client_goal
1401  client.send_goal(client_goal)
1402  ah.set_client(client)
1403  ah.wait_inside()
1404  ah.set_succeeded()
1405  return ah
1406 
1407  def set_wav_path(self,parameter_name,blocking=True):
1408  ah = action_handle("set_wav_path", "set_wav_path", parameter_name, blocking, self.parse)
1409  if type(parameter_name) is str:
1410  self.wav_path = parameter_name
1411  else:
1412  message = "Invalid wav_path parameter specified, aborting..."
1413  rospy.logerr(message)
1414  print("parameter is:", parameter_name)
1415  ah.set_failed(2, message)
1416  return ah
1417 
1418 #------------------- General section -------------------#
1419  ## Sleep for a certain time.
1420  #
1421  # \param duration Duration in seconds to sleep.
1422  #
1423  def sleep(self,duration):
1424  ah = action_handle("sleep", "", str(duration), True, self.parse)
1425  if(self.parse):
1426  return ah
1427  else:
1428  ah.set_active()
1429  rospy.loginfo("Wait for %f sec",duration)
1430  rospy.sleep(duration)
1431  ah.set_succeeded()
1432  return ah
1433 
1434  ## Waits for user input.
1435  #
1436  # Waits either for a user input or until timeout is reached.
1437  #
1438  # \param duration Duration in seconds for timeout.
1439  #
1440  # \todo TODO: implement waiting for timeout
1441  def wait_for_input(self,duration=0):
1442  ah = action_handle("wait", "input", str(duration), True, self.parse)
1443  if(self.parse):
1444  return ah
1445  else:
1446  ah.set_active()
1447 
1448  if (duration != 0):
1449  rospy.logerr("Wait with duration not implemented yet") # \todo TODO: implement waiting with duration
1450 
1451  rospy.loginfo("Wait for user input...")
1452  retVal = six.moves.input()
1453  rospy.loginfo("...got string <<%s>>",retVal)
1454  ah.set_succeeded()
1455  return retVal
1456 
1457 #------------------- action_handle section -------------------#
1458 ## Action handle class.
1459 #
1460 # The action handle is used to implement asynchronous behaviour within the script.
1462  ## Initializes the action handle.
1463  def __init__(self, function_name, component_name, parameter_name, blocking, parse):
1464  global graph
1465  self.parent_node = ""
1466  self.error_code = -1
1467  self.success = False
1468  self.message = ""
1469  self.function_name = function_name
1470  self.component_name = component_name
1471  self.parameter_name = parameter_name
1472  self.state = ScriptState.UNKNOWN
1473  self.blocking = blocking
1474  self.parse = parse
1475  self.level = int(rospy.get_param("/script_server/level",100))
1476  self.state_pub = rospy.Publisher("/script_server/state", ScriptState, queue_size=1)
1477  self.AppendNode(blocking)
1478  self.client = None
1479  self.client_state = GoalStatus.LOST
1480  self.client_mode = ""
1481 
1482  ## Sets the actionlib client.
1483  def set_client(self,client):
1484  self.client = client
1485 
1486  ## Sets the execution state to active, if not paused
1487  def set_active(self,mode=""):
1488  if mode != "": # not processing an actionlib client
1489  self.client_mode = mode
1490  self.client_state = GoalStatus.ACTIVE
1491  self.check_pause()
1492  self.state = ScriptState.ACTIVE
1493  self.error_code = -1
1494  self.PublishState()
1495 
1496  global ah_counter
1497  ah_counter += 1
1498 
1499  ## Checks for pause
1500  def check_pause(self):
1501  param_string = "/script_server/pause"
1502  while bool(rospy.get_param(param_string,False)):
1503  rospy.logwarn("Script is paused...")
1504  self.state = ScriptState.PAUSED
1505  self.PublishState()
1506  rospy.sleep(1)
1507  if self.state == ScriptState.PAUSED:
1508  rospy.loginfo("...continuing script")
1509 
1510  ## Sets the execution state to succeeded.
1511  def set_succeeded(self,message=""):
1512  if self.client_mode != "": # not processing an actionlib client
1513  self.client_state = GoalStatus.SUCCEEDED
1514  self.state = ScriptState.SUCCEEDED
1515  self.error_code = 0
1516  self.success = True
1517  self.message = message
1518  self.PublishState()
1519 
1520  global ah_counter
1521  ah_counter -= 1
1522 
1523  ## Sets the execution state to failed.
1524  def set_failed(self,error_code,message=""):
1525  if self.client_mode != "": # not processing an actionlib client
1526  self.client_state = GoalStatus.ABORTED
1527  self.state = ScriptState.FAILED
1528  self.error_code = error_code
1529  self.success = False
1530  self.message = message
1531  self.PublishState()
1532 
1533  global ah_counter
1534  ah_counter -= 1
1535 
1536  ## Gets the state of an action handle.
1537  def get_state(self):
1538  if self.client_mode != "": # not processing an actionlib client
1539  return self.client_state
1540  elif self.client == None:
1541  return GoalStatus.LOST
1542  else:
1543  return self.client.get_state()
1544 
1545  ## Gets the error code of an action handle.
1546  def get_error_code(self):
1547  return self.error_code
1548 
1549  ## Returns the graphstring.
1550  def GetGraphstring(self):
1551  if type(self.parameter_name) is str:
1552  graphstring = str(datetime.datetime.utcnow())+"_"+self.function_name+"_"+self.component_name+"_"+self.parameter_name
1553  else:
1554  graphstring = str(datetime.datetime.utcnow())+"_"+self.function_name+"_"+self.component_name
1555  return graphstring
1556 
1557  ## Gets level of function name.
1558  def GetLevel(self,function_name):
1559  if (function_name == "move"):
1560  level = 0
1561  elif (function_name == "init"):
1562  level = 1
1563  elif (function_name == "stop"):
1564  level = 1
1565  elif (function_name == "sleep"):
1566  level = 2
1567  else:
1568  level = 100
1569  return level
1570 
1571  ## Appends a registered function to the graph.
1572  def AppendNode(self, blocking=True):
1573  global graph
1574  global graph_wait_list
1575  global last_node
1576  graphstring = self.GetGraphstring()
1577  if self.parse:
1578  if ( self.level >= self.GetLevel(self.function_name)):
1579  #print "adding " + graphstring + " to graph"
1580  graph.add_edge(last_node, graphstring)
1581  for waiter in graph_wait_list:
1582  graph.add_edge(waiter, graphstring)
1583  graph_wait_list=[]
1584  if blocking:
1585  last_node = graphstring
1586  else:
1587  self.parent_node = graphstring
1588  #else:
1589  #print "not adding " + graphstring + " to graph"
1590  #else:
1591  #self.PublishState()
1592 
1593  ## Publishs the state of the action handle
1594  def PublishState(self):
1595  script_state = ScriptState()
1596  script_state.header.stamp = rospy.Time.now()
1597  script_state.function_name = self.function_name
1598  script_state.component_name = self.component_name
1599  script_state.full_graph_name = self.GetGraphstring()
1600  if ( type(self.parameter_name) is str ):
1601  script_state.parameter_name = self.parameter_name
1602  else:
1603  script_state.parameter_name = ""
1604  script_state.state = self.state
1605  script_state.error_code = self.error_code
1606  self.state_pub.publish(script_state)
1607 
1608  ## Handles wait.
1609  #
1610  # This function is meant to be uses directly in the script.
1611  #
1612  # \param duration Duration for timeout.
1613  def wait(self, duration=None):
1614  global ah_counter
1615  ah_counter += 1
1616  self.blocking = True
1617  self.wait_for_finished(duration,True)
1618 
1619  ## Handles inside wait.
1620  #
1621  # This function is meant to be uses inside the simple_script_server.
1622  #
1623  # \param duration Duration for timeout.
1624  def wait_inside(self, duration=None):
1625  if self.blocking:
1626  self.wait_for_finished(duration,True)
1627  else:
1628  Thread(target=self.wait_for_finished, args=(duration,False,)).start()
1629  return self.error_code
1630 
1631  ## Waits for the action to be finished.
1632  #
1633  # If duration is specified, waits until action is finished or timeout is reached.
1634  #
1635  # \param duration Duration for timeout.
1636  # \param logging Enables or disables logging for this wait.
1637  def wait_for_finished(self, duration, logging):
1638  global graph_wait_list
1639  if(self.parse):
1640  if(self.parent_node != ""):
1641  graph_wait_list.append(self.parent_node)
1642  return
1643 
1644  if self.error_code <= 0:
1645  if duration is None:
1646  if logging:
1647  rospy.loginfo("Wait for <<%s>> reaching <<%s>>...",self.component_name, self.parameter_name)
1648  self.client.wait_for_result()
1649  else:
1650  if logging:
1651  rospy.loginfo("Wait for <<%s>> reached <<%s>> (max %f secs)...",self.component_name, self.parameter_name,duration)
1652  if not self.client.wait_for_result(rospy.Duration(duration)):
1653  message = "Timeout while waiting for <<%s>> to reach <<%s>>. Continuing..."%(self.component_name, self.parameter_name)
1654  if logging:
1655  rospy.logerr(message)
1656  self.set_failed(10, message)
1657  return
1658  # check state of action server
1659  #print self.client.get_state()
1660  if self.client.get_state() != GoalStatus.SUCCEEDED:
1661  message = "...<<%s>> could not reach <<%s>>, aborting..."%(self.component_name, self.parameter_name)
1662  if logging:
1663  rospy.logerr(message)
1664  self.set_failed(11, message)
1665  return
1666  if logging:
1667  rospy.loginfo("...<<%s>> reached <<%s>>",self.component_name, self.parameter_name)
1668  else:
1669  message = "Execution of <<%s>> to <<%s>> was aborted, wait not possible. Continuing..."%(self.component_name, self.parameter_name)
1670  rospy.logwarn(message)
1671  self.set_failed(self.error_code, message)
1672  return
1673 
1674  self.set_succeeded() # full success
1675 
1676  ## Cancel action
1677  #
1678  # Cancels action goal(s).
1679  def cancel(self):
1680  self.client.cancel_all_goals()
def string_action(self, component_name, data, blocking)
Allows to trigger actions of the type cob_actions/SetString.
def calculate_point_time(self, start_pos, end_pos, default_vel, default_acc)
def recover(self, component_name, blocking=True)
Recovers different components.
def say(self, component_name, parameter_name, blocking=True)
Say some text.
def halt(self, component_name, blocking=True)
Halts different components.
def get_error_code(self)
Gets the error code of an action handle.
def _determine_desired_velocity(self, default_vel, start_pos, component_name, joint_names, speed_factor, urdf_vel)
def Parse(self)
Function to generate graph view of script.
def wait_for_finished(self, duration, logging)
Waits for the action to be finished.
def move_traj(self, component_name, parameter_name, blocking, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False)
Deals with all kind of trajectory movements for different components.
def set_mimic(self, component_name, parameter_name, blocking=False)
Set the mimic of the cob_mimic component.
def AppendNode(self, blocking=True)
Appends a registered function to the graph.
def Start(self)
Function to start the script.
def trigger_action(self, component_name, action_name, blocking=True)
Allows to trigger actions of the type actionlib/TestAction.
def move_rel(self, component_name, parameter_name, blocking=True, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False)
Relative movement Deals with all kind of relative movements for different components.
def Run(self)
Dummy function for main run function.
def get_state(self)
Gets the state of an action handle.
def init(self, component_name, blocking=True)
Initializes different components.
def set_active(self, mode="")
Sets the execution state to active, if not paused.
def play(self, component_name, parameter_name, blocking=True)
Play a sound file.
def stop(self, component_name, mode="omni", blocking=True)
Stops different components.
def wait_for_input(self, duration=0)
Waits for user input.
def calculate_point_velocities(self, prev, curr, post, stop_at_waypoints=False)
def move(self, component_name, parameter_name, blocking=True, mode=None, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False)
Deals with all kind of movements for different components.
Script class from which all script inherit.
def compose_color(self, component_name, parameter_name)
Set the color of the cob_light component.
def set_client(self, client)
Sets the actionlib client.
def Initialize(self)
Dummy function for initialization.
def __init__(self, parse=False)
Initializes simple_script_server class.
def move_base_rel(self, component_name, parameter_name=[0, blocking=True)
Relative movement of the base.
def PublishState(self)
Publishs the state of the action handle.
def compose_trajectory(self, component_name, parameter_name, speed_factor=1.0, urdf_vel=False, default_vel=None, stop_at_waypoints=False)
Parse and compose trajectory message.
def set_failed(self, error_code, message="")
Sets the execution state to failed.
def trigger(self, component_name, service_name, blocking=True)
Deals with all kind of trigger services for different components.
def GetLevel(self, function_name)
Gets level of function name.
def wait_inside(self, duration=None)
Handles inside wait.
def __init__(self, function_name, component_name, parameter_name, blocking, parse)
Initializes the action handle.
def move_base(self, component_name, parameter_name, blocking, mode)
Deals with movements of the base.
def set_light(self, component_name, parameter_name, blocking=False)
def set_succeeded(self, message="")
Sets the execution state to succeeded.


cob_script_server
Author(s): Florian Weisshardt
autogenerated on Wed Apr 7 2021 03:03:06