ssm_descriptor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2015 Airbus
00004 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00005 #
00006 # Licensed under the Apache License, Version 2.0 (the "License");
00007 # you may not use this file except in compliance with the License.
00008 # You may obtain a copy of the License at
00009 #
00010 #   http://www.apache.org/licenses/LICENSE-2.0
00011 #
00012 # Unless required by applicable law or agreed to in writing, software
00013 # distributed under the License is distributed on an "AS IS" BASIS,
00014 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015 # See the License for the specific language governing permissions and
00016 # limitations under the License.
00017 
00018 import rospy
00019 import os
00020 import datetime
00021 import sys
00022 from airbus_ssm_core import ssm_skill_provider
00023 from airbus_ssm_core.ssm_scxml_interpreter import get_pkg_dir_from_prefix
00024 from importlib import import_module
00025 from xml.etree import ElementTree
00026 
00027 def StrTimeStamped():
00028     return datetime.datetime.now().strftime("%Y_%m_%d_%H:%M")
00029 
00030 
00031 class SkillXMLDescriptor():
00032     
00033     def __init__(self, input_file, output_file):
00034         #Check the existence of the skill xml file
00035         self._input_file = get_pkg_dir_from_prefix(input_file)
00036         if(os.path.isfile(self._input_file) == False):
00037             self._input_file = get_pkg_dir_from_prefix("${airbus_ssm_core}/resources/"+input_file)
00038             if(os.path.isfile(self._input_file) == False):
00039                 rospy.logerr(["[SkillXMLDescriptor] '%s' not found !"%input_file])
00040                 sys.exit(-1)
00041         #Check the output file
00042         self._output_file = get_pkg_dir_from_prefix(output_file)
00043         try:
00044             f = open(self._output_file, 'w')
00045             f.close()
00046         except Exception as e:
00047             rospy.logerr("[SkillXMLDescriptor] error during output file creation : %s"%e)
00048             sys.exit(-1) 
00049 
00050         #Create the SkillProvider
00051         try:
00052             self._SkillProvider = ssm_skill_provider.SkillProvider(self._input_file)
00053         except Exception as e:
00054             rospy.logerr("[SkillXMLDescriptor] error during skill provider creation : %s"%e)
00055             sys.exit(-1)
00056         
00057         self.describeXMLFile()
00058         
00059     
00060     def describeXMLFile(self):
00061         
00062         _tree = ElementTree.parse(self._input_file)
00063         _root = _tree.getroot()
00064         _descriptors = []
00065         _descriptors.append("Skill XML File Descriptor")
00066         _descriptors.append("XML File : '%s'"%self._input_file)
00067         _descriptors.append("Creation : '%s'"%StrTimeStamped())
00068         _descriptors.append("\n-----------------------------------------------------------------\n")
00069         for skill in _root:
00070             try:
00071                 _state = self._SkillProvider.load(skill.attrib["name"])()
00072             except Exception as e:
00073                 rospy.logerr("[SkillXMLDescriptor] error during skill '%s' loading : %s"%(skill.attrib["name"],e))
00074                 sys.exit(-1)
00075                 
00076             _path = (import_module(skill.attrib["module"], skill.attrib["pkg"]).__file__)
00077             _path = _path[:-1]
00078             _descr = self.find_descriptions(_path, skill.attrib["class"])
00079             _outcomes = self.find_outcomes(_state)
00080             _iokeys = self.find_iokey(_state)
00081             _descriptor = self.createDescriptor(skill.attrib["name"], skill.attrib["class"], _descr, _outcomes, _iokeys)
00082             for line in _descriptor:
00083                 _descriptors.append(line)
00084             
00085         self.writeTxtFile(_descriptors)
00086         
00087     
00088     def createDescriptor(self, name, class_, decription, outcomes, io_keys):
00089         descriptor = []
00090         descriptor.append("State Name : '%s' (used in the scxml file)"%name)
00091         descriptor.append("Class      : '%s'"%(class_))
00092         descriptor.append(outcomes)
00093         descriptor.append(io_keys)
00094         descriptor.append('')
00095         for line in decription:
00096             descriptor.append(line)
00097         descriptor.append("\n-----------------------------------------------------------------\n")
00098         return descriptor
00099         
00100             
00101     def writeTxtFile(self, descriptors):
00102         file = open(self._output_file, 'w')
00103         for line in descriptors:
00104             file.write("%s\n"%line)
00105         file.close()
00106         
00107         rospy.loginfo("[SkillXMLDescriptor] XML file : '%s'"%self._input_file)
00108         rospy.loginfo("[SkillXMLDescriptor] Description file created : '%s'"%self._output_file)
00109         
00110     
00111     def find_outcomes(self, state):
00112         _str = "Outcomes   : "
00113         _outcomes = state.get_registered_outcomes()
00114         for outcome in _outcomes:
00115             if(outcome != "preempt"):
00116                 _str = _str +"'"+outcome + "', "
00117         _str = _str[:-2]
00118         
00119         return _str
00120         
00121     def find_iokey(self, state):
00122         _str = "User data  : "
00123         _keys = state.get_registered_input_keys()
00124         if(len(_keys) > 2):
00125             for key in _keys:
00126                  if(key != "skill" and key != "logfile"):
00127                      _str = _str +"'"+key + "', "
00128             _str = _str[:-2]
00129         else:
00130             _str = "No user data."
00131         
00132         return _str
00133         
00134     def find_descriptions(self, file, state_py):
00135         _file = open(file).readlines()
00136         _search_str = "class "+state_py
00137         _file = [x.strip('\n') for x in _file]
00138         _found = 0
00139         #Find the class we are working on
00140         for num, line in enumerate(_file,1):
00141             if _search_str in line:
00142                 _found = num
00143                 break
00144         _file = _file[_found:]
00145         #Limit the reseach on this class (find the next one if it exist and keep only what is before that)
00146         _found = -1
00147         _search_str = "class "
00148         for num, line in enumerate(_file[2:],1):
00149             if _search_str in line:
00150                 _found = num
00151                 break
00152         if(_found != -1):
00153             _file = _file[:_found]
00154         #Look for a decription tag
00155         _found = -1
00156         _search_str = "'''@SSM"
00157         for num, line in enumerate(_file,1):
00158             if _search_str in line:
00159                 _found = num
00160                 break
00161         if(_found != -1):
00162             _file = _file[_found:]
00163             #Look for the end decription tag
00164             _search_str = "'''"
00165             for num, line in enumerate(_file[1:],1):
00166                 if _search_str in line:
00167                     _found = num
00168             _str = []
00169             for line in _file[:_found]:
00170                 _str.append(line.strip())
00171         else:
00172             _str = ["No description found for this class.","Check the python file.", str(file)]
00173             rospy.logwarn("[SkillDescriptor] : No description found for the class : '%s'"%state_py)
00174         
00175         return _str
00176 
00177 
00178 if __name__ == '__main__':
00179     rospy.init_node("ssm_descriptor")
00180     input_file = rospy.get_param('/ssm_descriptor/skill_xml_file', default='empty_register.xml')
00181     output_file = rospy.get_param('/ssm_descriptor/output_file', default='/tmp/descriptor.txt')
00182     descriptor = SkillXMLDescriptor(input_file, output_file)
00183     


airbus_ssm_core
Author(s): Ludovic Delval
autogenerated on Thu Jun 6 2019 17:59:28