simple_script_server.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 #################################################################
00003 ##\file
00004 #
00005 # \note
00006 #   Copyright (c) 2010 \n
00007 #   Fraunhofer Institute for Manufacturing Engineering
00008 #   and Automation (IPA) \n\n
00009 #
00010 #################################################################
00011 #
00012 # \note
00013 #   Project name: care-o-bot
00014 # \note
00015 #   ROS stack name: cob_command_tools
00016 # \note
00017 #   ROS package name: cob_script_server
00018 #
00019 # \author
00020 #   Author: Florian Weisshardt, email:florian.weisshardt@ipa.fhg.de
00021 # \author
00022 #   Supervised by: Florian Weisshardt, email:florian.weisshardt@ipa.fhg.de
00023 #
00024 # \date Date of creation: Aug 2010
00025 #
00026 # \brief
00027 #   Implements script server functionalities.
00028 #
00029 #################################################################
00030 #
00031 # Redistribution and use in source and binary forms, with or without
00032 # modification, are permitted provided that the following conditions are met:
00033 #
00034 #     - Redistributions of source code must retain the above copyright
00035 #       notice, this list of conditions and the following disclaimer. \n
00036 #     - Redistributions in binary form must reproduce the above copyright
00037 #       notice, this list of conditions and the following disclaimer in the
00038 #       documentation and/or other materials provided with the distribution. \n
00039 #     - Neither the name of the Fraunhofer Institute for Manufacturing
00040 #       Engineering and Automation (IPA) nor the names of its
00041 #       contributors may be used to endorse or promote products derived from
00042 #       this software without specific prior written permission. \n
00043 #
00044 # This program is free software: you can redistribute it and/or modify
00045 # it under the terms of the GNU Lesser General Public License LGPL as 
00046 # published by the Free Software Foundation, either version 3 of the 
00047 # License, or (at your option) any later version.
00048 # 
00049 # This program is distributed in the hope that it will be useful,
00050 # but WITHOUT ANY WARRANTY; without even the implied warranty of
00051 # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00052 # GNU Lesser General Public License LGPL for more details.
00053 # 
00054 # You should have received a copy of the GNU Lesser General Public 
00055 # License LGPL along with this program. 
00056 # If not, see <http://www.gnu.org/licenses/>.
00057 #
00058 #################################################################
00059 
00060 import time
00061 import os
00062 import sys
00063 import types
00064 import thread
00065 import commands
00066 import math
00067 
00068 # ROS imports
00069 import roslib
00070 roslib.load_manifest('cob_script_server')
00071 import rospy
00072 import actionlib
00073 
00074 # msg imports
00075 from trajectory_msgs.msg import *
00076 from geometry_msgs.msg import *
00077 from move_base_msgs.msg import *
00078 from tf.transformations import *
00079 from std_msgs.msg import String,ColorRGBA
00080 from control_msgs.msg import *
00081 
00082 # care-o-bot includes
00083 from cob_sound.msg import *
00084 from cob_script_server.msg import *
00085 from cob_srvs.srv import *
00086 
00087 # graph includes
00088 import pygraphviz as pgv
00089 
00090 graph=""
00091 graph_wait_list=[]
00092 function_counter = 0
00093 ah_counter = 0
00094 graph = pgv.AGraph()
00095 graph.node_attr['shape']='box'
00096 last_node = "Start"
00097 
00098 ## Script class from which all script inherit.
00099 #
00100 # Implements basic functionalities for all scripts.
00101 class script():
00102         def __init__(self):
00103                 # use filename as nodename
00104                 filename = os.path.basename(sys.argv[0])
00105                 self.basename, extension = os.path.splitext(filename)
00106                 rospy.init_node(self.basename)
00107                 self.graph_pub = rospy.Publisher("/script_server/graph", String)
00108 
00109         ## Dummy function for initialization
00110         def Initialize(self):
00111                 pass
00112 
00113         ## Dummy function for main run function
00114         def Run(self):
00115                 pass
00116 
00117         ## Function to start the script
00118         #
00119         # First does a simulated turn and then calls Initialize() and Run().
00120         def Start(self):
00121                 self.Parse()
00122                 global ah_counter
00123                 ah_counter = 0
00124                 self.sss = simple_script_server()
00125                 rospy.loginfo("Starting <<%s>> script...",self.basename)
00126                 self.Initialize()
00127                 self.Run()
00128                 # wait until last threaded action finishes
00129                 rospy.loginfo("Wait for script to finish...")
00130                 while ah_counter != 0:
00131                         rospy.sleep(1)
00132                 rospy.loginfo("...script finished.")
00133         
00134         ## Function to generate graph view of script.
00135         #
00136         # Starts the script in simulation mode and calls Initialize() and Run().
00137         def Parse(self):
00138                 rospy.loginfo("Start parsing...")
00139                 global graph
00140                 global function_counter
00141                 function_counter = 0
00142                 # run script in simulation mode
00143                 self.sss = simple_script_server(parse=True)
00144                 self.Initialize()
00145                 self.Run()
00146                 
00147                 # save graph on parameter server for further processing
00148 #               self.graph = graph
00149                 rospy.set_param("/script_server/graph", graph.string())
00150                 self.graph_pub.publish(graph.string())
00151                 rospy.loginfo("...parsing finished")
00152                 function_counter = 0
00153                 return graph.string()
00154 
00155 ## Simple script server class.
00156 #
00157 # Implements the python interface for the script server.
00158 class simple_script_server:
00159         ## Initializes simple_script_server class.
00160         #
00161         # \param parse Defines wether to run script in simulation for graph generation or not
00162         def __init__(self, parse=False):
00163                 global graph
00164                 self.ns_global_prefix = "/script_server"
00165                 self.wav_path = ""
00166                 self.parse = parse
00167                 
00168                 # init publishers
00169                 self.pub_light = rospy.Publisher('/light_controller/command', ColorRGBA)
00170                 
00171                 rospy.sleep(1) # we have to wait here until publishers are ready, don't ask why
00172 
00173     #------------------- Init section -------------------#
00174         ## Initializes different components.
00175         #
00176         # Based on the component, the corresponding init service will be called.
00177         #
00178         # \param component_name Name of the component.
00179         def init(self,component_name,blocking=True):
00180                 return self.trigger(component_name,"init",blocking=blocking)
00181 
00182         ## Stops different components.
00183         #
00184         # Based on the component, the corresponding stop service will be called.
00185         #
00186         # \param component_name Name of the component.
00187         def stop(self,component_name,mode="omni",blocking=True):
00188                 #return self.trigger(component_name,"stop",blocking=blocking)
00189                 if component_name == "base":
00190                         ah = action_handle("stop", component_name, "", False, self.parse)
00191                         if(self.parse):
00192                                 return ah
00193                         else:
00194                                 ah.set_active(mode="service")
00195         
00196                         rospy.loginfo("<<stop>> <<%s>>", component_name)
00197         
00198                         # call action server
00199                         if(mode == None or mode == ""):
00200                                 action_server_name = "/move_base"
00201                         elif(mode == "omni"):
00202                                 action_server_name = "/move_base"
00203                         elif(mode == "diff"):
00204                                 action_server_name = "/move_base_diff"
00205                         elif(mode == "linear"):
00206                                 action_server_name = "/move_base_linear"
00207                         else:
00208                                 rospy.logerr("no valid navigation mode given for %s, aborting...",component_name)
00209                                 print "navigation mode is:",mode
00210                                 ah.set_failed(33)
00211                                 return ah
00212 
00213                         rospy.logdebug("calling %s action server",action_server_name)
00214                         client = actionlib.SimpleActionClient(action_server_name, MoveBaseAction)
00215                         
00216                         if blocking:
00217                                 # trying to connect to server
00218                                 rospy.logdebug("waiting for %s action server to start",action_server_name)
00219                                 if not client.wait_for_server(rospy.Duration(5)):
00220                                         # error: server did not respond
00221                                         rospy.logerr("%s action server not ready within timeout, aborting...", action_server_name)
00222                                         ah.set_failed(4)
00223                                         return ah
00224                                 else:
00225                                         rospy.logdebug("%s action server ready",action_server_name)
00226 
00227                         # cancel all goals
00228                         client.cancel_all_goals()
00229                         
00230                         ah.set_succeeded() # full success
00231                         return ah       
00232                 else:
00233                         return self.trigger(component_name,"stop",blocking=blocking)
00234 
00235         ## Recovers different components.
00236         #
00237         # Based on the component, the corresponding recover service will be called.
00238         #
00239         # \param component_name Name of the component.
00240         def recover(self,component_name,blocking=True):
00241                 return self.trigger(component_name,"recover",blocking=blocking)
00242 
00243         ## Deals with all kind of trigger services for different components.
00244         #
00245         # Based on the component and service name, the corresponding trigger service will be called.
00246         #
00247         # \param component_name Name of the component.
00248         # \param service_name Name of the trigger service.
00249         # \param blocking Service calls are always blocking. The parameter is only provided for compatibility with other functions.
00250         def trigger(self,component_name,service_name,blocking=True, planning=False):
00251                 ah = action_handle(service_name, component_name, "", blocking, self.parse)
00252                 if(self.parse):
00253                         return ah
00254                 else:
00255                         ah.set_active(mode="service")
00256 
00257                 rospy.loginfo("<<%s>> <<%s>>", service_name, component_name)
00258                 service_full_name = "/" + component_name + "_controller/" + service_name
00259                 
00260                 if blocking:
00261                         # check if service is available
00262                         try:
00263                                 rospy.wait_for_service(service_full_name,rospy.get_param('server_timeout',3))
00264                         except rospy.ROSException, e:
00265                                 error_message = "%s"%e
00266                                 rospy.logerr("...<<%s>> service of <<%s>> not available, error: %s",service_name, component_name, error_message)
00267                                 ah.set_failed(4)
00268                                 return ah
00269 
00270                 # check if service is callable
00271                 try:
00272                         init = rospy.ServiceProxy(service_full_name,Trigger)
00273                         #print init()
00274                         #resp = init()
00275                         if blocking:
00276                                 rospy.loginfo("Wait for <<%s>> to <<%s>>...", component_name, service_name)
00277                                 resp = init()
00278                         else:
00279                                 thread.start_new_thread(init,())
00280                 except rospy.ServiceException, e:
00281                         error_message = "%s"%e
00282                         rospy.logerr("...calling <<%s>> service of <<%s>> not successfull, error: %s",service_name, component_name, error_message)
00283                         ah.set_failed(10)
00284                         return ah
00285 
00286                 if blocking:
00287                         # evaluate sevice response
00288                         if not resp.success.data:
00289                                 rospy.logerr("...<<%s>> <<%s>> not successfull, error: %s",service_name, component_name, resp.error_message.data) 
00290                                 ah.set_failed(10)
00291                                 return ah
00292                 
00293                         # full success
00294                         rospy.loginfo("...<<%s>> is <<%s>>", component_name, service_name)
00295                         ah.set_succeeded() # full success
00296                 return ah
00297 
00298 #------------------- Move section -------------------#
00299         ## Deals with all kind of movements for different components.
00300         #
00301         # Based on the component, the corresponding move functions will be called.
00302         #
00303         # \param component_name Name of the component.
00304         # \param parameter_name Name of the parameter on the ROS parameter server.
00305         # \param blocking Bool value to specify blocking behaviour.
00306         def move(self,component_name,parameter_name,blocking=True, mode=None):
00307                 if component_name == "base":
00308                         return self.move_base(component_name,parameter_name,blocking, mode)
00309                 elif component_name == "arm" and mode=="planned":
00310                         return self.move_planned(component_name,parameter_name,blocking)
00311                 else:
00312                         return self.move_traj(component_name,parameter_name,blocking)
00313 
00314         ## Deals with movements of the base.
00315         #
00316         # A target will be sent to the actionlib interface of the move_base node.
00317         #
00318         # \param component_name Name of the component.
00319         # \param parameter_name Name of the parameter on the ROS parameter server.
00320         # \param blocking Bool value to specify blocking behaviour.
00321         def move_base(self,component_name,parameter_name,blocking, mode):
00322                 ah = action_handle("move", component_name, parameter_name, blocking, self.parse)
00323                 if(self.parse):
00324                         return ah
00325                 else:
00326                         ah.set_active()
00327                 
00328                 if(mode == None or mode == ""):
00329                         rospy.loginfo("Move <<%s>> to <<%s>>",component_name,parameter_name)
00330                 else:
00331                         rospy.loginfo("Move <<%s>> to <<%s>> using <<%s>> mode",component_name,parameter_name,mode)
00332                 
00333                 # get joint values from parameter server
00334                 if type(parameter_name) is str:
00335                         if not rospy.has_param(self.ns_global_prefix + "/" + component_name + "/" + parameter_name):
00336                                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",self.ns_global_prefix + "/" + component_name + "/" + parameter_name)
00337                                 ah.set_failed(2)
00338                                 return ah
00339                         param = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/" + parameter_name)
00340                 else:
00341                         param = parameter_name
00342                 
00343                 # check trajectory parameters
00344                 if not type(param) is list: # check outer list
00345                                 rospy.logerr("no valid parameter for %s: not a list, aborting...",component_name)
00346                                 print "parameter is:",param
00347                                 ah.set_failed(3)
00348                                 return ah
00349                 else:
00350                         #print i,"type1 = ", type(i)
00351                         DOF = 3
00352                         if not len(param) == DOF: # check dimension
00353                                 rospy.logerr("no valid parameter for %s: dimension should be %d and is %d, aborting...",component_name,DOF,len(param))
00354                                 print "parameter is:",param
00355                                 ah.set_failed(3)
00356                                 return ah
00357                         else:
00358                                 for i in param:
00359                                         #print i,"type2 = ", type(i)
00360                                         if not ((type(i) is float) or (type(i) is int)): # check type
00361                                                 #print type(i)
00362                                                 rospy.logerr("no valid parameter for %s: not a list of float or int, aborting...",component_name)
00363                                                 print "parameter is:",param
00364                                                 ah.set_failed(3)
00365                                                 return ah
00366                                         else:
00367                                                 rospy.logdebug("accepted parameter %f for %s",i,component_name)
00368 
00369                 # convert to pose message
00370                 pose = PoseStamped()
00371                 pose.header.stamp = rospy.Time.now()
00372                 pose.header.frame_id = "/map"
00373                 pose.pose.position.x = param[0]
00374                 pose.pose.position.y = param[1]
00375                 pose.pose.position.z = 0.0
00376                 q = quaternion_from_euler(0, 0, param[2])
00377                 pose.pose.orientation.x = q[0]
00378                 pose.pose.orientation.y = q[1]
00379                 pose.pose.orientation.z = q[2]
00380                 pose.pose.orientation.w = q[3]
00381                 
00382                 # call action server
00383                 if(mode == None or mode == ""):
00384                         action_server_name = "/move_base"
00385                 elif(mode == "omni"):
00386                         action_server_name = "/move_base"
00387                 elif(mode == "diff"):
00388                         action_server_name = "/move_base_diff"
00389                 elif(mode == "linear"):
00390                         action_server_name = "/move_base_linear"
00391                 else:
00392                         rospy.logerr("no valid navigation mode given for %s, aborting...",component_name)
00393                         print "navigation mode is:",mode
00394                         ah.set_failed(33)
00395                         return ah
00396                 
00397                 rospy.logdebug("calling %s action server",action_server_name)
00398                 client = actionlib.SimpleActionClient(action_server_name, MoveBaseAction)
00399                 # trying to connect to server
00400                 rospy.logdebug("waiting for %s action server to start",action_server_name)
00401                 if not client.wait_for_server(rospy.Duration(5)):
00402                         # error: server did not respond
00403                         rospy.logerr("%s action server not ready within timeout, aborting...", action_server_name)
00404                         ah.set_failed(4)
00405                         return ah
00406                 else:
00407                         rospy.logdebug("%s action server ready",action_server_name)
00408 
00409                 # sending goal
00410                 client_goal = MoveBaseGoal()
00411                 client_goal.target_pose = pose
00412                 #print client_goal
00413                 client.send_goal(client_goal)
00414                 ah.set_client(client)
00415 
00416                 ah.wait_inside()
00417 
00418                 return ah
00419 
00420         ## Deals with all kind of trajectory movements for different components.
00421         #
00422         # A trajectory will be sent to the actionlib interface of the corresponding component.
00423         #
00424         # \param component_name Name of the component.
00425         # \param parameter_name Name of the parameter on the ROS parameter server.
00426         # \param blocking Bool value to specify blocking behaviour.
00427         def move_traj(self,component_name,parameter_name,blocking):
00428                 ah = action_handle("move", component_name, parameter_name, blocking, self.parse)
00429                 if(self.parse):
00430                         return ah
00431                 else:
00432                         ah.set_active()
00433                 
00434                 rospy.loginfo("Move <<%s>> to <<%s>>",component_name,parameter_name)
00435                 
00436                 # get joint_names from parameter server
00437                 param_string = self.ns_global_prefix + "/" + component_name + "/joint_names"
00438                 if not rospy.has_param(param_string):
00439                                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",param_string)
00440                                 ah.set_failed(2)
00441                                 return ah
00442                 joint_names = rospy.get_param(param_string)
00443                 
00444                 # check joint_names parameter
00445                 if not type(joint_names) is list: # check list
00446                                 rospy.logerr("no valid joint_names for %s: not a list, aborting...",component_name)
00447                                 print "joint_names are:",joint_names
00448                                 ah.set_failed(3)
00449                                 return ah
00450                 else:
00451                         for i in joint_names:
00452                                 #print i,"type1 = ", type(i)
00453                                 if not type(i) is str: # check string
00454                                         rospy.logerr("no valid joint_names for %s: not a list of strings, aborting...",component_name)
00455                                         print "joint_names are:",param
00456                                         ah.set_failed(3)
00457                                         return ah
00458                                 else:
00459                                         rospy.logdebug("accepted joint_names for component %s",component_name)
00460                 
00461                 # get joint values from parameter server
00462                 if type(parameter_name) is str:
00463                         if not rospy.has_param(self.ns_global_prefix + "/" + component_name + "/" + parameter_name):
00464                                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",self.ns_global_prefix + "/" + component_name + "/" + parameter_name)
00465                                 ah.set_failed(2)
00466                                 return ah
00467                         param = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/" + parameter_name)
00468                 else:
00469                         param = parameter_name
00470 
00471                 # check trajectory parameters
00472                 if not type(param) is list: # check outer list
00473                                 rospy.logerr("no valid parameter for %s: not a list, aborting...",component_name)
00474                                 print "parameter is:",param
00475                                 ah.set_failed(3)
00476                                 return ah
00477 
00478                 traj = []
00479 
00480                 for point in param:
00481                         #print point,"type1 = ", type(point)
00482                         if type(point) is str:
00483                                 if not rospy.has_param(self.ns_global_prefix + "/" + component_name + "/" + point):
00484                                         rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",self.ns_global_prefix + "/" + component_name + "/" + point)
00485                                         ah.set_failed(2)
00486                                         return ah
00487                                 point = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/" + point)
00488                                 point = point[0] # \todo TODO: hack because only first point is used, no support for trajectories inside trajectories
00489                                 #print point
00490                         elif type(point) is list:
00491                                 rospy.logdebug("point is a list")
00492                         else:
00493                                 rospy.logerr("no valid parameter for %s: not a list of lists or strings, aborting...",component_name)
00494                                 print "parameter is:",param
00495                                 ah.set_failed(3)
00496                                 return ah
00497 
00498                         # here: point should be list of floats/ints
00499                         #print point
00500                         if not len(point) == len(joint_names): # check dimension
00501                                 rospy.logerr("no valid parameter for %s: dimension should be %d and is %d, aborting...",component_name,len(joint_names),len(point))
00502                                 print "parameter is:",param
00503                                 ah.set_failed(3)
00504                                 return ah
00505 
00506                         for value in point:
00507                                 #print value,"type2 = ", type(value)
00508                                 if not ((type(value) is float) or (type(value) is int)): # check type
00509                                         #print type(value)
00510                                         rospy.logerr("no valid parameter for %s: not a list of float or int, aborting...",component_name)
00511                                         print "parameter is:",param
00512                                         ah.set_failed(3)
00513                                         return ah
00514                         
00515                                 rospy.logdebug("accepted value %f for %s",value,component_name)
00516                         traj.append(point)
00517 
00518                 rospy.logdebug("accepted trajectory for %s",component_name)
00519                 
00520                 # convert to ROS trajectory message
00521                 traj_msg = JointTrajectory()
00522                 traj_msg.header.stamp = rospy.Time.now()+rospy.Duration(0.5)
00523                 traj_msg.joint_names = joint_names
00524                 point_nr = 0
00525                 for point in traj:
00526                         point_nr = point_nr + 1
00527                         point_msg = JointTrajectoryPoint()
00528                         point_msg.positions = point
00529                         point_msg.velocities = [0]*len(joint_names)
00530                         point_msg.time_from_start=rospy.Duration(3*point_nr) # this value is set to 3 sec per point. \todo TODO: read from parameter
00531                         traj_msg.points.append(point_msg)
00532 
00533                 # call action server
00534                 action_server_name = "/" + component_name + '_controller/follow_joint_trajectory'
00535                 rospy.logdebug("calling %s action server",action_server_name)
00536                 client = actionlib.SimpleActionClient(action_server_name, FollowJointTrajectoryAction)
00537                 # trying to connect to server
00538                 rospy.logdebug("waiting for %s action server to start",action_server_name)
00539                 if not client.wait_for_server(rospy.Duration(5)):
00540                         # error: server did not respond
00541                         rospy.logerr("%s action server not ready within timeout, aborting...", action_server_name)
00542                         ah.set_failed(4)
00543                         return ah
00544                 else:
00545                         rospy.logdebug("%s action server ready",action_server_name)
00546                 
00547                 # set operation mode to position
00548                 #if not component_name == "arm":
00549                 #       self.set_operation_mode(component_name,"position")
00550                 #self.set_operation_mode(component_name,"position")             
00551 
00552                 # sending goal
00553                 client_goal = FollowJointTrajectoryGoal()
00554                 client_goal.trajectory = traj_msg
00555                 #print client_goal
00556                 client.send_goal(client_goal)
00557                 ah.set_client(client)
00558 
00559                 ah.wait_inside()
00560                 return ah
00561                 
00562         ## Relative movement of the base
00563         #
00564         # \param component_name Name of component; here always "base".
00565         # \param parameter_name List of length 3: (item 1 & 2) relative x and y translation [m]; (item 3) relative rotation about z axis [rad].
00566         # \param blocking Bool value to specify blocking behaviour.
00567         # 
00568         # # throws error code 3 in case of invalid parameter_name vector 
00569         def move_base_rel(self, component_name, parameter_name=[0,0,0], blocking=True): 
00570                 ah = action_handle("move_base_rel", component_name, parameter_name, blocking, self.parse)
00571                 if(self.parse):
00572                         return ah
00573                 else:
00574                         ah.set_active(mode="topic")
00575 
00576                 rospy.loginfo("Move base relatively by <<%s>>", parameter_name)
00577 
00578                 # step 0: check validity of parameters:
00579                 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)):
00580                         rospy.logerr("Non-numeric parameter_name list, aborting move_base_rel")
00581                         print("parameter_name must be numeric list of length 3; (relative x and y transl [m], relative rotation [rad])")
00582                         ah.set_failed(3)
00583                         return ah
00584                 if math.sqrt(parameter_name[0]**2 + parameter_name[1]**2) >= 0.15:
00585                         rospy.logerr("Maximal relative translation step exceeded, aborting move_base_rel")
00586                         print("Maximal relative translation step is 0.1 m")
00587                         ah.set_failed(3)
00588                         return(ah)
00589                 if abs(parameter_name[2]) >= math.pi/2:
00590                         rospy.logerr("Maximal relative rotation step exceeded, aborting move_base_rel")
00591                         print("Maximal relative rotation step is pi/2")
00592                         ah.set_failed(3)
00593                         return(ah)
00594 
00595                 # step 1: determine duration of motion so that upper thresholds for both translational as well as rotational velocity are not exceeded
00596                 max_trans_vel = 0.05 # [m/s]
00597                 max_rot_vel = 0.2 # [rad/s]
00598                 duration_trans_sec = math.sqrt(parameter_name[0]**2 + parameter_name[1]**2) / max_trans_vel
00599                 duration_rot_sec = abs(parameter_name[2] / max_rot_vel)
00600                 duration_sec = max(duration_trans_sec, duration_rot_sec)
00601                 duration_ros = rospy.Duration.from_sec(duration_sec) # duration of motion in ROS time
00602 
00603                 # step 2: determine actual velocities based on calculated duration
00604                 x_vel = parameter_name[0] / duration_sec
00605                 y_vel = parameter_name[1] / duration_sec
00606                 rot_vel = parameter_name[2] / duration_sec
00607 
00608                 # step 3: send constant velocity command to base_controller for the calculated duration of motion
00609                 pub = rospy.Publisher('/base_controller/command_safe', Twist)  # todo: use Matthias G.'s safe_command
00610                 twist = Twist()
00611                 twist.linear.x = x_vel
00612                 twist.linear.y = y_vel
00613                 twist.angular.z = rot_vel
00614                 r = rospy.Rate(10) # send velocity commands at 10 Hz
00615                 end_time = rospy.Time.now() + duration_ros
00616                 while not rospy.is_shutdown() and rospy.Time.now() < end_time:
00617                         pub.publish(twist)
00618                         r.sleep()
00619 
00620                 ah.set_succeeded()
00621                 return ah
00622 
00623         
00624         ## Set the operation mode for different components.
00625         #
00626         # Based on the component, the corresponding set_operation_mode service will be called.
00627         #
00628         # \param component_name Name of the component.
00629         # \param mode Name of the operation mode to set.
00630         # \param blocking Service calls are always blocking. The parameter is only provided for compatibility with other functions.
00631         def set_operation_mode(self,component_name,mode,blocking=True, planning=False):
00632                 #rospy.loginfo("setting <<%s>> to operation mode <<%s>>",component_name, mode)
00633                 rospy.set_param("/" + component_name + "_controller/OperationMode",mode) # \todo TODO: remove and only use service call
00634                 #rospy.wait_for_service("/" + component_name + "_controller/set_operation_mode")
00635                 try:
00636                         set_operation_mode = rospy.ServiceProxy("/" + component_name + "_controller/set_operation_mode", SetOperationMode)
00637                         req = SetOperationModeRequest()
00638                         req.operation_mode.data = mode
00639                         #print req
00640                         resp = set_operation_mode(req)
00641                         #print resp
00642                 except rospy.ServiceException, e:
00643                         print "Service call failed: %s"%e
00644                 
00645 #------------------- LED section -------------------#
00646         ## Set the color of the cob_light component.
00647         #
00648         # The color is given by a parameter on the parameter server.
00649         #
00650         # \param parameter_name Name of the parameter on the parameter server which holds the rgb values.
00651         def set_light(self,parameter_name,blocking=False):
00652                 ah = action_handle("set", "light", parameter_name, blocking, self.parse)
00653                 if(self.parse):
00654                         return ah
00655                 else:
00656                         ah.set_active(mode="topic")
00657 
00658                 rospy.loginfo("Set light to <<%s>>",parameter_name)
00659                 
00660                 # get joint values from parameter server
00661                 if type(parameter_name) is str:
00662                         if not rospy.has_param(self.ns_global_prefix + "/light/" + parameter_name):
00663                                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",self.ns_global_prefix + "/light/" + parameter_name)
00664                                 return 2
00665                         param = rospy.get_param(self.ns_global_prefix + "/light/" + parameter_name)
00666                 else:
00667                         param = parameter_name
00668                         
00669                 # check color parameters
00670                 if not type(param) is list: # check outer list
00671                         rospy.logerr("no valid parameter for light: not a list, aborting...")
00672                         print "parameter is:",param
00673                         ah.error_code = 3
00674                         return ah
00675                 else:
00676                         if not len(param) == 3: # check dimension
00677                                 rospy.logerr("no valid parameter for light: dimension should be 3 (r,g,b) and is %d, aborting...",len(param))
00678                                 print "parameter is:",param
00679                                 ah.error_code = 3
00680                                 return ah
00681                         else:
00682                                 for i in param:
00683                                         #print i,"type1 = ", type(i)
00684                                         if not ((type(i) is float) or (type(i) is int)): # check type
00685                                                 #print type(i)
00686                                                 rospy.logerr("no valid parameter for light: not a list of float or int, aborting...")
00687                                                 print "parameter is:",param
00688                                                 ah.error_code = 3
00689                                                 return ah
00690                                         else:
00691                                                 rospy.logdebug("accepted parameter %f for light",i)
00692                 
00693                 # convert to ColorRGBA message
00694                 color = ColorRGBA()
00695                 color.r = param[0]
00696                 color.g = param[1]
00697                 color.b = param[2]
00698                 color.a = 1 # Transparency
00699 
00700                 # publish color         
00701                 self.pub_light.publish(color)
00702                 
00703                 ah.set_succeeded()
00704                 ah.error_code = 0
00705                 return ah
00706 
00707 #-------------------- Sound section --------------------#
00708         ## Say some text.
00709         #
00710         # 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.
00711         #
00712         # \param parameter_name Name of the parameter
00713         # \param language Language to use for the TTS system
00714         def say(self,parameter_name,blocking=True):
00715                 component_name = "sound"
00716                 ah = action_handle("say", component_name, parameter_name, blocking, self.parse)
00717                 if(self.parse):
00718                         return ah
00719                 else:
00720                         ah.set_active()
00721                         
00722                 text = ""
00723                 
00724                 # get values from parameter server
00725                 language = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/language","en")
00726                 if type(parameter_name) is str:
00727                         if not rospy.has_param(self.ns_global_prefix + "/" + component_name + "/" + language + "/" + parameter_name):
00728                                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",self.ns_global_prefix + "/" + component_name + "/" + language + "/" + parameter_name)
00729                                 ah.set_failed(2)
00730                                 return ah
00731                         param = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/" + language + "/" + parameter_name)
00732                 else:
00733                         param = parameter_name
00734                 
00735                 # check parameters
00736                 if not type(param) is list: # check list
00737                                 rospy.logerr("no valid parameter for %s: not a list, aborting...",component_name)
00738                                 print "parameter is:",param
00739                                 ah.set_failed(3)
00740                                 return ah
00741                 else:
00742                         for i in param:
00743                                 #print i,"type1 = ", type(i)
00744                                 if not type(i) is str:
00745                                         rospy.logerr("no valid parameter for %s: not a list of strings, aborting...",component_name)
00746                                         print "parameter is:",param
00747                                         ah.set_failed(3)
00748                                         return ah
00749                                 else:
00750                                         text = text + i + " "
00751                                         rospy.logdebug("accepted parameter <<%s>> for <<%s>>",i,component_name)
00752 
00753                 rospy.loginfo("Saying <<%s>>",text)
00754                 
00755                 # call action server
00756                 action_server_name = "/sound_controller/say"
00757                 rospy.logdebug("calling %s action server",action_server_name)
00758                 client = actionlib.SimpleActionClient(action_server_name, SayAction)
00759                 # trying to connect to server
00760                 rospy.logdebug("waiting for %s action server to start",action_server_name)
00761                 if not client.wait_for_server(rospy.Duration(5)):
00762                         # error: server did not respond
00763                         rospy.logerr("%s action server not ready within timeout, aborting...", action_server_name)
00764                         ah.set_failed(4)
00765                         return ah
00766                 else:
00767                         rospy.logdebug("%s action server ready",action_server_name)
00768 
00769                 # sending goal
00770                 client_goal = SayGoal()
00771                 client_goal.text.data = text
00772                 #print client_goal
00773                 client.send_goal(client_goal)
00774                 ah.set_client(client)
00775 
00776                 ah.wait_inside()
00777                 return ah
00778 
00779         ## Play a sound file.
00780         #
00781         # \param parameter_name Name of the parameter
00782         # \param language Language to use
00783         def play(self,parameter_name,blocking=True):
00784                 component_name = "sound"
00785                 ah = action_handle("play", component_name, parameter_name, False, self.parse)
00786                 if(self.parse):
00787                         return ah
00788                 else:
00789                         ah.set_active(mode="system")
00790                 
00791                 language = rospy.get_param(self.ns_global_prefix + "/" + component_name + "/language","en")
00792                 if self.wav_path == "":
00793                         wav_path = commands.getoutput("rospack find cob_script_server")
00794                 else:
00795                         wav_path = self.wav_path
00796                 filename = wav_path + "/common/files/" + language + "/" + parameter_name + ".wav"
00797                 
00798                 rospy.loginfo("Playing <<%s>>",filename)
00799                 #self.soundhandle.playWave(filename)
00800                 
00801                 #\todo TODO: check if file exists
00802                 # if filename exists:
00803                 #       do ...
00804                 # else 
00805                 #       ah.set_fail(3)
00806                 #       return ah
00807                 
00808                 if blocking:
00809                         ret = os.system("aplay -q " + filename)
00810                         if ret != 0:
00811                                 ah.set_failed(99)
00812                                 return ah
00813                 else:
00814                         os.system("aplay -q " + filename + "&") # TODO how to check if execution failed (e.g. file could be found)?
00815                 ah.set_succeeded()
00816                 return ah
00817                 
00818         def set_wav_path(self,parameter_name,blocking=True):
00819                 if type(parameter_name) is str:
00820                         self.wav_path = parameter_name
00821                 else:
00822                         rospy.logerr("invalid wav_path parameter specified, aborting...")
00823                         print "parameter is:", parameter_name
00824                         ah.set_failed(2)
00825                         return ah               
00826 
00827 #------------------- General section -------------------#
00828         ## Sleep for a certain time.
00829         #
00830         # \param duration Duration in seconds to sleep.
00831         #
00832         def sleep(self,duration):
00833                 ah = action_handle("sleep", "", str(duration), True, self.parse)
00834                 if(self.parse):
00835                         return ah
00836                 else:
00837                         ah.set_active()
00838                 rospy.loginfo("Wait for %f sec",duration)
00839                 rospy.sleep(duration)
00840                 
00841                 ah.set_succeeded()
00842                 return ah
00843 
00844         ## Waits for user input.
00845         #
00846         # Waits either for a user input or until timeout is reached.
00847         #
00848         # \param duration Duration in seconds for timeout.
00849         # 
00850         # \todo TODO: implement waiting for timeout
00851         def wait_for_input(self,duration=0):
00852                 ah = action_handle("wait", "input", str(duration), True, self.parse)
00853                 if(self.parse):
00854                         return ah
00855                 else:
00856                         ah.set_active()
00857                 
00858                 if (duration != 0):
00859                         rospy.logerr("Wait with duration not implemented yet") # \todo TODO: implement waiting with duration
00860                 
00861                 rospy.loginfo("Wait for user input...")
00862                 retVal = raw_input()
00863                 rospy.loginfo("...got string <<%s>>",retVal)
00864                 ah.set_succeeded()
00865                 return retVal
00866 
00867 #------------------- action_handle section -------------------# 
00868 ## Action handle class.
00869 #
00870 # The action handle is used to implement asynchronous behaviour within the script.
00871 class action_handle:
00872         ## Initializes the action handle.
00873         def __init__(self, function_name, component_name, parameter_name, blocking, parse):
00874                 global graph
00875                 global function_counter
00876                 self.parent_node = ""
00877                 self.error_code = -1
00878                 self.wait_log = False
00879                 self.function_counter = function_counter
00880                 self.function_name = function_name
00881                 self.component_name = component_name
00882                 self.parameter_name = parameter_name
00883                 self.state = ScriptState.UNKNOWN
00884                 self.blocking = blocking
00885                 self.parse = parse
00886                 self.level = int(rospy.get_param("/script_server/level",100))
00887                 self.state_pub = rospy.Publisher("/script_server/state", ScriptState)
00888                 self.AppendNode(blocking)
00889                 self.client = actionlib.SimpleActionClient("dummy",ScriptAction)
00890                 self.client_state = 9
00891                 self.client_mode = ""
00892 
00893         ## Sets the actionlib client.
00894         def set_client(self,client):
00895                 self.client = client
00896 
00897         ## Sets the execution state to active, if not paused
00898         def set_active(self,mode=""):
00899                 if mode != "": # not processing an actionlib client
00900                         self.client_mode = mode
00901                         self.client_state = 1
00902                 self.check_pause()
00903                 self.state = ScriptState.ACTIVE
00904                 self.error_code = -1
00905                 self.PublishState()
00906                 
00907                 global ah_counter
00908                 ah_counter += 1
00909                 
00910         ## Checks for pause
00911         def check_pause(self):
00912                 param_string = "/script_server/pause"
00913                 while bool(rospy.get_param(param_string,False)):
00914                         rospy.logwarn("Script is paused...")
00915                         self.state = ScriptState.PAUSED
00916                         self.PublishState()
00917                         rospy.sleep(1)
00918                 if self.state == ScriptState.PAUSED:
00919                         rospy.loginfo("...continuing script")
00920                 
00921         ## Sets the execution state to succeeded.
00922         def set_succeeded(self):
00923                 if self.client_mode != "": # not processing an actionlib client
00924                         self.client_state = 3
00925                 self.state = ScriptState.SUCCEEDED
00926                 self.error_code = 0
00927                 self.PublishState()
00928                 
00929                 global ah_counter
00930                 ah_counter -= 1
00931                 
00932         ## Sets the execution state to failed.
00933         def set_failed(self,error_code):
00934                 if self.client_mode != "": # not processing an actionlib client
00935                         self.client_state = 4
00936                 self.state = ScriptState.FAILED
00937                 self.error_code = error_code
00938                 self.PublishState()
00939 
00940                 global ah_counter
00941                 ah_counter -= 1
00942                 
00943         ## Gets the state of an action handle.
00944         def get_state(self):
00945                 if self.client_mode != "": # not processing an actionlib client
00946                         return self.client_state
00947                 else:
00948                         return self.client.get_state()
00949 
00950         ## Gets the error code of an action handle.
00951         def get_error_code(self):
00952                 return self.error_code
00953         
00954         ## Returns the graphstring.
00955         def GetGraphstring(self):
00956                 if type(self.parameter_name) is types.StringType:
00957                         graphstring = str(self.function_counter)+"_"+self.function_name+"_"+self.component_name+"_"+self.parameter_name
00958                 else:
00959                         graphstring = str(self.function_counter)+"_"+self.function_name+"_"+self.component_name
00960                 return graphstring
00961 
00962         ## Gets level of function name.
00963         def GetLevel(self,function_name):
00964                 if (function_name == "move"):
00965                         level = 0
00966                 elif (function_name == "init"):
00967                         level = 1
00968                 elif (function_name == "stop"):
00969                         level = 1
00970                 elif (function_name == "sleep"):
00971                         level = 2
00972                 else:
00973                         level = 100
00974                 return level
00975                 
00976         ## Appends a registered function to the graph.
00977         def AppendNode(self, blocking=True):
00978                 global graph
00979                 global graph_wait_list
00980                 global function_counter
00981                 global last_node
00982                 graphstring = self.GetGraphstring()
00983                 if self.parse:
00984                         if ( self.level >= self.GetLevel(self.function_name)):
00985                                 #print "adding " + graphstring + " to graph"
00986                                 graph.add_edge(last_node, graphstring)
00987                                 for waiter in graph_wait_list:
00988                                         graph.add_edge(waiter, graphstring)
00989                                 graph_wait_list=[]
00990                                 if blocking:
00991                                         last_node = graphstring
00992                                 else:
00993                                         self.parent_node = graphstring
00994                         #else:
00995                                 #print "not adding " + graphstring + " to graph"
00996                 #else:
00997                         #self.PublishState()
00998                 function_counter += 1
00999                 
01000         ## Publishs the state of the action handle
01001         def PublishState(self):
01002                 script_state = ScriptState()
01003                 script_state.header.stamp = rospy.Time.now()
01004                 script_state.number = self.function_counter
01005                 script_state.function_name = self.function_name
01006                 script_state.component_name = self.component_name
01007                 script_state.full_graph_name = self.GetGraphstring()
01008                 if ( type(self.parameter_name) is str ):
01009                         script_state.parameter_name = self.parameter_name
01010                 else:
01011                         script_state.parameter_name = ""
01012                 script_state.state = self.state
01013                 script_state.error_code = self.error_code
01014                 self.state_pub.publish(script_state)
01015                 
01016         ## Handles wait.
01017         #
01018         # This function is meant to be uses directly in the script.
01019         #
01020         # \param duration Duration for timeout.
01021         def wait(self, duration=None):
01022                 global ah_counter
01023                 ah_counter += 1
01024                 self.blocking = True
01025                 self.wait_for_finished(duration,True)
01026 
01027         ## Handles inside wait.
01028         #
01029         # This function is meant to be uses inside the simple_script_server.
01030         #
01031         # \param duration Duration for timeout.
01032         def wait_inside(self, duration=None):
01033                 if self.blocking:
01034                         self.wait_for_finished(duration,True)
01035                 else:
01036                         thread.start_new_thread(self.wait_for_finished,(duration,False,))
01037                 return self.error_code
01038         
01039         ## Waits for the action to be finished.
01040         #
01041         # If duration is specified, waits until action is finished or timeout is reached.
01042         #
01043         # \param duration Duration for timeout.
01044         # \param logging Enables or disables logging for this wait.
01045         def wait_for_finished(self, duration, logging):
01046                 global graph_wait_list
01047                 if(self.parse):
01048                         if(self.parent_node != ""):
01049                                 graph_wait_list.append(self.parent_node)
01050                         return
01051 
01052                 if self.error_code <= 0:                        
01053                         if duration is None:
01054                                 if logging:
01055                                         rospy.loginfo("Wait for <<%s>> reaching <<%s>>...",self.component_name, self.parameter_name)
01056                                 self.client.wait_for_result()
01057                         else:
01058                                 if logging:
01059                                         rospy.loginfo("Wait for <<%s>> reached <<%s>> (max %f secs)...",self.component_name, self.parameter_name,duration)
01060                                 if not self.client.wait_for_result(rospy.Duration(duration)):
01061                                         if logging:
01062                                                 rospy.logerr("Timeout while waiting for <<%s>> to reach <<%s>>. Continuing...",self.component_name, self.parameter_name)
01063                                         self.set_failed(10)
01064                                         return
01065                         # check state of action server
01066                         #print self.client.get_state()
01067                         if self.client.get_state() != 3:
01068                                 if logging:
01069                                         rospy.logerr("...<<%s>> could not reach <<%s>>, aborting...",self.component_name, self.parameter_name)
01070                                 self.set_failed(11)
01071                                 return
01072 
01073                         if logging:
01074                                 rospy.loginfo("...<<%s>> reached <<%s>>",self.component_name, self.parameter_name)
01075                 else:
01076                         rospy.logwarn("Execution of <<%s>> to <<%s>> was aborted, wait not possible. Continuing...",self.component_name, self.parameter_name)
01077                         self.set_failed(self.error_code)
01078                         return
01079                         
01080                 self.set_succeeded() # full success
01081         
01082         ## Cancel action
01083         #
01084         # Cancels action goal(s).
01085         def cancel(self):
01086                 self.client.cancel_all_goals()


cob_script_server
Author(s): Florian Weisshardt
autogenerated on Thu Aug 27 2015 12:42:55