script_server.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #       http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import time
00019 import inspect
00020 
00021 import rospy
00022 import actionlib
00023 
00024 from cob_script_server.msg import *
00025 from cob_script_server.srv import *
00026 from simple_script_server import *
00027 
00028 sss = simple_script_server()
00029 
00030 ## Script server class which inherits from script class.
00031 #
00032 # Implements actionlib interface for the script server.
00033 #
00034 class script_server():
00035         ## Initializes the actionlib interface of the script server.
00036         #
00037         def __init__(self):
00038                 self.ns_global_prefix = "/script_server"
00039                 self.script_action_server = actionlib.SimpleActionServer(self.ns_global_prefix, ScriptAction, self.execute_cb, False)
00040                 self.script_action_server.start()
00041                 self.compose_trajectory_service = rospy.Service('~compose_trajectory', ComposeTrajectory, self.handle_compose_trajectory)
00042 
00043 #------------------- Service section -------------------#
00044         def handle_compose_trajectory(self, req):
00045                 print "compose trajectory", req.component_name, req.parameter_name
00046                 traj_msg, error_code = sss.compose_trajectory(req.component_name, req.parameter_name)
00047                 if error_code != 0:
00048                         return None
00049                 res = ComposeTrajectoryResponse()
00050                 res.trajectory = traj_msg
00051                 return res
00052 
00053 #------------------- Actionlib section -------------------#
00054         ## Executes actionlib callbacks.
00055         #
00056         # \param server_goal ScriptActionGoal
00057         #
00058         def execute_cb(self, server_goal):
00059                 server_result = ScriptActionResult().result
00060                 if server_goal.function_name == None or server_goal.function_name.strip() == "":
00061                         rospy.logerr("function name cannot be blank")
00062                         return
00063 
00064                 if server_goal.function_name in dir(sss):
00065                         func = getattr(sss, server_goal.function_name)
00066                         argspec = inspect.getargspec(func)
00067                         args = {}
00068                         for arg in argspec.args:
00069                                 if arg in dir(server_goal):
00070                                         serverArg = getattr(server_goal, arg)
00071                                         if type(serverArg) == str:
00072                                                 try:
00073                                                         serverArg = eval(serverArg)
00074                                                 except:
00075                                                         pass
00076                                         args[arg] = serverArg
00077 
00078                         handle01 = func(*(), **args)
00079                 else:
00080                         rospy.logerr("function <<%s>> not supported", server_goal.function_name)
00081                         self.script_action_server.set_aborted(server_result)
00082                         return
00083 
00084                 if 'get_error_code' in dir(handle01):
00085                         server_result.error_code = handle01.get_error_code()
00086                 else:
00087                         rospy.logwarn("unexpected action result type <<%s>> for function %s", type(handle01), server_goal.function_name)
00088                 if server_result.error_code == 0:
00089                         rospy.logdebug("action result success")
00090                         self.script_action_server.set_succeeded(server_result)
00091                 else:
00092                         rospy.logerr("action result error, error_code: " + str(server_result.error_code))
00093                         self.script_action_server.set_aborted(server_result)
00094 
00095 ## Main routine for running the script server
00096 #
00097 if __name__ == '__main__':
00098         rospy.init_node('script_server')
00099         script_server()
00100         rospy.loginfo("script_server is running")
00101         rospy.spin()


cob_script_server
Author(s): Florian Weisshardt
autogenerated on Sun Jun 9 2019 20:20:12