xml_file_bridge.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 ## @author Fabian Wenzelmann
00004 #  @date 03/10/2011
00005 import roslib
00006 roslib.load_manifest('face_contour_detector')
00007 import rospy
00008 import xml_image_information
00009 from face_contour_detector.srv import *
00010 from face_contour_detector.msg import *
00011 import image_information
00012 import cv_bridge
00013 
00014 ## @package face_contour_detector.image_information.xml_file_bridge
00015 #  This package implements the services srv/XMLReader.srv and srv/XMLWriter.srv It is used to save and read image datebase xml files.
00016 #  @author Fabian Wenzelmann
00017 
00018 ## @brief Handler to save a xml file, see srv/XMLWriter.srv
00019 #  @param req the request object
00020 def save_handler(req):
00021     database = xml_image_information.XMLImageInformationDatabase()
00022     for image in req.images:
00023         database.append(_gen_dict(image))
00024     try:
00025         database.write_file(req.file_name)
00026         return XMLWriterResponse(True)
00027     except:
00028         raise
00029         return XMLWriterResponse(False)
00030 
00031 ## @brief handler to load a xml file, see srv/XMLReader.srv
00032 #  @param req request object
00033 def load_handler(req):
00034     path = req.file_name
00035     database = xml_image_information.XMLImageInformationDatabase()
00036     try:
00037         database.load_file(path)
00038         return XMLReaderResponse(_gen_list(database.images), True)
00039     except:
00040         raise
00041         return XMLReaderResponse([], False)
00042 
00043 ## @brief get default information about an image, see srv/ImageInformationBridge.srv        
00044 #  @param req request object
00045 def information_handler(req):
00046     extractor = image_information.InformationExtractor()
00047     extractor.add_default_extractors()
00048     bridge = cv_bridge.CvBridge()
00049     img = bridge.imgmsg_to_cv(req.input_image)
00050     props = extractor.to_dict(img)
00051     entries = []
00052     for entry_name, (value, type_name) in props.items():
00053         entries.append(xml_image_entry(entry_name.encode("ascii"), type_name.encode("ascii"), str(value).encode("ascii")))
00054     return ImageInformationBridgeResponse(xml_image(entries))
00055 
00056 def _gen_dict(image):
00057     result = {}
00058     for entry in image.entries:
00059         get_value = None
00060         if entry.type == "int":
00061             get_value = int
00062         elif entry.type == "float":
00063             get_value = float
00064         else:
00065             get_value = str
00066         result[entry.entry_name] = get_value(entry.content), entry.type
00067     return result
00068     
00069 def _gen_list(images):
00070     image_list = []
00071     for image in images:
00072         entries = []
00073         for entry_name, (value, type_name) in image.items():
00074             entries.append( xml_image_entry(entry_name.encode("ascii"), type_name.encode("ascii"), str(value).encode("ascii")) )
00075         image_list.append(xml_image(entries))
00076     return image_list
00077     
00078 def xml_file_bridge_init_node():
00079     rospy.init_node("xml_file_bridge_server")
00080     s1 = rospy.Service('xml_file_bridge', XMLWriter, save_handler)
00081     s2 = rospy.Service("xml_file_bridge_loader", XMLReader, load_handler)
00082     s3 = rospy.Service("image_information", ImageInformationBridge, information_handler)
00083     rospy.spin()
00084     
00085 if __name__ == "__main__":
00086     xml_file_bridge_init_node()
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


face_contour_detector
Author(s): Fabian Wenzelmann and Julian Schmid
autogenerated on Wed Dec 26 2012 16:18:17