$search
00001 import roslib 00002 roslib.load_manifest('semantic_model_web_interface') 00003 00004 import mongo_ros as mr 00005 import semanticmodel.msg as smm 00006 import sensor_msgs.msg as sm 00007 import cv 00008 import cv_bridge 00009 import os 00010 from os import path 00011 from . import site_root, lock, DB_PORT, DB_NAME, DB_HOST 00012 import logging 00013 from logging import config 00014 import pymongo as pm 00015 import semanticmodel.db as sdb 00016 00017 config.fileConfig(path.join(site_root, 'logging.conf')) 00018 log = logging.getLogger('semantic_model_web.db') 00019 00020 cluster_collections = {} 00021 image_collections = {} 00022 bridge = cv_bridge.CvBridge() 00023 00024 POSITIONS = { 00025 'green_room': (20, 20, 8), 00026 'pool_room': (17, 35, 7), 00027 'white_lab': (34, 43, 10), 00028 'cafe': (30, 15, 7), 00029 'research_hallway': (5, 22, 7) 00030 } 00031 00032 def filter_query(q): 00033 #q['$or'] = [{'num_vertical': {'$gt': 5}}, {'num_vertical': {'$exists': 00034 # False}}] 00035 return q 00036 00037 def get_cluster_collection(run): 00038 with lock: 00039 return get_cached_collection(cluster_collections, run, 'blobs', 00040 smm.BlobMessage) 00041 00042 def get_image_collection(run): 00043 with lock: 00044 return get_cached_collection(image_collections, 00045 run, 'images', sm.Image) 00046 00047 def get_cached_collection(colls, run, c, t): 00048 if run not in colls: 00049 colls[run] =\ 00050 mr.MessageCollection(DB_NAME, sdb.collection_name(run, c), t) 00051 return colls[run] 00052 00053 def list_runs(): 00054 conn = pm.Connection(host=DB_HOST, port=DB_PORT) 00055 db = conn[DB_NAME] 00056 runs = db['runs'] 00057 return [('run{0}'.format(run['id']), 00058 '{0}.bag'.format(run['bag_file'])) for run in runs.find({})] 00059 00060 def run_info(run): 00061 conn = pm.Connection(host=DB_HOST, port=DB_PORT) 00062 db = conn[DB_NAME] 00063 runs = db['runs'] 00064 id = int(run[3:]) 00065 cursor = runs.find({'id': id}) 00066 return next(cursor, None) 00067 00068 def image_file_loc(i, run): 00069 """ 00070 @param i: Id of cluster 00071 @param run: Run id 00072 00073 Ensure that the file for the image of the cluster is available (download 00074 if necessary), and return its site-relative URL 00075 """ 00076 with lock: 00077 coll = get_image_collection(run) 00078 meta = coll.find_one({'cluster_id': i}, True, sort_by='creation_time', 00079 ascending=False) 00080 relative_path = path.join('static/images', 00081 run, 00082 '{0}.jpg'.format(meta['blob_id'])) 00083 filename = path.join(site_root, relative_path) 00084 log.debug("Looking for image file {0}".format(relative_path)) 00085 if not path.exists(filename): 00086 log.info("{0} not found: getting from db".format(relative_path)) 00087 msg, _ = coll.find_one(meta) 00088 img = bridge.imgmsg_to_cv(msg) 00089 d = path.dirname(filename) 00090 if not path.exists(d): 00091 os.makedirs(d) 00092 cv.SaveImage(filename, img) 00093 else: 00094 log.debug(" File found; not downloading") 00095 return '/'+relative_path 00096 00097 def next_id(coll, id): 00098 cursor = coll.find(filter_query({'id': {'$gt': id}})).sort('id', pm.ASCENDING) 00099 item = next(cursor, None) 00100 if item: 00101 return item['id'] 00102 00103 def prev_id(coll, id): 00104 cursor = coll.find(filter_query({'id': {'$lt': id}})).sort('id', pm.DESCENDING) 00105 item = next(cursor, None) 00106 if item: 00107 return item['id'] 00108 00109 def semantic_query(args): 00110 q = {} 00111 c = args.get('color') 00112 if c: 00113 q['color'] = c 00114 s = args.get('size') 00115 if s == 'small': 00116 q['diameter'] = {'$lt': 0.2} 00117 elif s == 'medium': 00118 q['diameter'] = {'$gte': 0.2, '$lt': 0.8} 00119 elif s == 'large': 00120 q['diameter'] = {'$gte': 0.8} 00121 shape = args.get('shape') 00122 if shape == 'planar': 00123 q['c01'] = {'$gt': 0.5} 00124 elif shape == 'curved': 00125 q['c01'] = {'$lte': 0.5} 00126 s = args.get('loc') 00127 if s: 00128 pos = POSITIONS.get(s) 00129 if pos: 00130 radius = pos[2] 00131 q['x'] = {'$lt': pos[0]+radius, '$gt': pos[0]-radius} 00132 q['y'] = {'$lt': pos[1]+radius, '$gt': pos[1]-radius} 00133 00134 return q 00135 00136 00137