def worker_qsrs(chunk):
    (file_, path, soma_objects, config) = chunk

    e = utils.load_e(path, file_)

    dynamic_args = {}
    try:
        dynamic_args['argd'] = config['argd_args']
        dynamic_args['qtcbs'] = config['qtcbs_args']
        dynamic_args["qstag"] = {"params" : config['qstag_args']}
        dynamic_args['filters'] = {"median_filter": {"window": config['qsr_mean_window']}}  # This has been updated since ECAI paper.
    except KeyError:
        print "check argd, qtcbs, qstag parameters in config file"


    joint_types = {'head': 'head', 'torso': 'torso', 'left_hand': 'hand', 'right_hand': 'hand', 'left_knee': 'knee', 'right_knee': 'knee',
                   'left_shoulder': 'shoulder', 'right_shoulder': 'shoulder', 'head-torso': 'tpcc-plane'}
    object_types = joint_types.copy()
    add_objects = []
    for region, objects in ce.get_soma_objects().items():
        for o in objects:
            add_objects.append(o)
            try:
                generic_object = "_".join(o.split("_")[:-1])
                object_types[o] = generic_object
            except:
                print "didnt add:", object
    dynamic_args["qstag"]["object_types"] = object_types

    """1. CREATE QSRs FOR joints & Object """
    qsrlib = QSRlib()

    qsrs_for=[]
    for ob in objects:
        qsrs_for.append((str(ob), 'left_hand'))
        qsrs_for.append((str(ob), 'right_hand'))
        qsrs_for.append((str(ob), 'torso'))
    dynamic_args['argd']["qsrs_for"] = qsrs_for
    dynamic_args['qtcbs']["qsrs_for"] = qsrs_for

    req = QSRlib_Request_Message(config['which_qsr'], input_data=e.map_world, dynamic_args=dynamic_args)
    e.qsr_object_frame = qsrlib.request_qsrs(req_msg=req)

    # print ">", e.qsr_object_frame.qstag.graphlets.histogram
    # for i in e.qsr_object_frame.qstag.episodes:
    #     print i
    # sys.exit(1)
    """2. CREATE QSRs for joints - TPCC"""
    # print "TPCC: ",
    # # e.qsr_joint_frame = get_joint_frame_qsrs(file, e.camera_world, joint_types, dynamic_args)
    # qsrs_for = [('head', 'torso', ob) if ob not in ['head', 'torso'] and ob != 'head-torso' else () for ob in joint_types.keys()]
    # dynamic_args['tpcc'] = {"qsrs_for": qsrs_for}
    # dynamic_args["qstag"]["params"] = {"min_rows": 1, "max_rows": 2, "max_eps": 4}
    # qsrlib = QSRlib()
    # req = QSRlib_Request_Message(which_qsr="tpcc", input_data=e.camera_world, dynamic_args=dynamic_args)
    # e.qsr_joints_frame = qsrlib.request_qsrs(req_msg=req)
    # # pretty_print_world_qsr_trace("tpcc", e.qsr_joints_frame)
    # # print e.qsr_joints_frame.qstag.graphlets.histogram
    utils.save_event(e, "Learning/QSR_Worlds")
def worker_qsrs(chunk):
    (file_, path, soma_objects, qsr_mean_window) = chunk
    e = utils.load_e(path, file_)

    dynamic_args = {}
    dynamic_args["qstag"] = {}
    dynamic_args['filters'] = {"median_filter": {"window": qsr_mean_window}}  # This has been updated since ECAI paper.

    """ADD OBJECT TYPES into DYNAMIC ARGS """
    joint_types = {'head': 'head', 'torso': 'torso', 'left_hand': 'hand', 'right_hand': 'hand', 'left_knee': 'knee', 'right_knee': 'knee',
                   'left_shoulder': 'shoulder', 'right_shoulder': 'shoulder', 'head-torso': 'tpcc-plane'}
    all_object_types = joint_types.copy()

    add_objects = []
    for region, objects in ce.get_soma_objects().items():
        for o in objects:
            add_objects.append(o)
            try:
                generic_object = "_".join(o.split("_")[:-1])
                all_object_types[o] = generic_object
            except:
                print "didnt add:", object

    dynamic_args["qstag"]["object_types"] = all_object_types

    """1. CREATE QSRs FOR Key joints & Object """
    print " QTC,QDC: "
    qsrlib = QSRlib()
    # print ">>", e.map_world.get_sorted_timestamps()

    # for t in e.map_world.trace:
    #     print "\nt", t
    #     for o, state in e.map_world.trace[t].objects.items():
    #         print o, state.x,state.y,state.z
    # sys.exit(1)

    req = QSRLib_param_mapping(e.map_world, dynamic_args, soma_objects)
    e.qsr_object_frame = qsrlib.request_qsrs(req_msg=req)

    # print ">", e.qsr_object_frame.qstag.graphlets.histogram
    # for i in e.qsr_object_frame.qstag.episodes:
    #     print i
    # sys.exit(1)
    """2. CREATE QSRs for joints - TPCC"""
    # print "TPCC: ",
    # # e.qsr_joint_frame = get_joint_frame_qsrs(file, e.camera_world, joint_types, dynamic_args)
    # qsrs_for = [('head', 'torso', ob) if ob not in ['head', 'torso'] and ob != 'head-torso' else () for ob in joint_types.keys()]
    # dynamic_args['tpcc'] = {"qsrs_for": qsrs_for}
    # dynamic_args["qstag"]["params"] = {"min_rows": 1, "max_rows": 2, "max_eps": 4}
    # qsrlib = QSRlib()
    # req = QSRlib_Request_Message(which_qsr="tpcc", input_data=e.camera_world, dynamic_args=dynamic_args)
    # e.qsr_joints_frame = qsrlib.request_qsrs(req_msg=req)
    # # pretty_print_world_qsr_trace("tpcc", e.qsr_joints_frame)
    # # print e.qsr_joints_frame.qstag.graphlets.histogram
    utils.save_event(e, "Learning/QSR_Worlds")
def worker_padd(chunk):
    (event_file, histogram_directory, lenth_codebook) = chunk
    # print "    ", event_file

    e = utils.load_e(histogram_directory, event_file)
    e.global_histogram = np.array([[0]*lenth_codebook])

    ind = len(e.temp_histogram)
    #Overlay the global histogram with the temp histogram
    e.global_histogram[0][:ind] = e.temp_histogram
    # utils.save_event(e)
    return (e.uuid, e.global_histogram[0])
def create_temp_histograms(qsr_path_, global_codebook, all_graphlets, batch):
    """sequentially create a temporary histogram whilst
    generating the codebook from observations"""
    wordids = []
    wordcts = []
    uuids = []

    for e_cnt, event_file in enumerate(batch):
        (date, time, uuid) = event_file.split("_")
        qsr_path = os.path.join(qsr_path_, date)

        #for e_cnt, event_file in sorted(enumerate(os.listdir(qsr_path))):
        #if event_file.replace(".p","") not in batch: continue
        e = utils.load_e(qsr_path, event_file)

        if len(e.qsr_object_frame.qstag.graphlets.histogram) == 0:
            print e_cnt, event_file, "len:0"
            continue

        e.temp_histogram = np.array([0] * (global_codebook.shape[0]))
        if e.label != "NA": e.uuid += "_" + e.label

        print "  ", e_cnt, e.uuid, "len:", len(
            e.qsr_object_frame.qstag.graphlets.histogram
        )  #, len(e.qsr_joints_frame.qstag.graphlets.histogram)
        # feature_spaces = [e.qsr_object_frame.qstag.graphlets, e.qsr_joints_frame.qstag.graphlets]
        feature_spaces = [e.qsr_object_frame.qstag.graphlets
                          ]  #, e.qsr_joints_frame.qstag.graphlets]

        for cnt, f in enumerate(feature_spaces):
            for freq, hash in zip(f.histogram, f.code_book):
                try:
                    ind = np.where(global_codebook == hash)[0][0]
                    e.temp_histogram[ind] += freq
                # If the hash doesn't exist in the global codebook yet - add it
                except IndexError:
                    global_codebook = np.append(global_codebook, hash)
                    e.temp_histogram = np.append(e.temp_histogram, freq)
                    all_graphlets = np.append(all_graphlets, f.graphlets[hash])
                    # print "\n>", hash, f.graphlets[hash]
        # print "> ",len(e.temp_histogram)
        # print global_codebook, e.temp_histogram, all_graphlets
        # print ">", np.nonzero(e.temp_histogram)[0]
        uuids.append(e.uuid)
        ids = np.nonzero(e.temp_histogram)[0]
        wordids.append(ids)
        wordcts.append(e.temp_histogram[ids])
        # print "<", e.temp_histogram[ids]
        utils.save_event(e, "Learning/Histograms")

    ret = (uuids, wordids, wordcts)
    return global_codebook, all_graphlets, ret
def create_temp_histograms(qsr_path, accu_path):
    """sequentially create a temporary histogram whilst
    generating the codebook from observations"""

    global_codebook = np.array([])
    all_graphlets = np.array([])

    for d_cnt, dir_ in sorted(enumerate(os.listdir(qsr_path))):
        directory = os.path.join(qsr_path, dir_)
        print "dir: ", directory, d_cnt, dir_

        for e_cnt, event_file in sorted(enumerate(os.listdir(directory))):
            e = utils.load_e(directory, event_file)

            if len(e.qsr_object_frame.qstag.graphlets.histogram) == 0:
                print "removed:", e_cnt, event_file
                continue
            e.temp_histogram = np.array([0] * (global_codebook.shape[0]))

            print "  ", d_cnt, e_cnt, e.uuid, "len:", len(e.qsr_object_frame.qstag.graphlets.histogram) #, len(e.qsr_joints_frame.qstag.graphlets.histogram)
            # feature_spaces = [e.qsr_object_frame.qstag.graphlets, e.qsr_joints_frame.qstag.graphlets]
            feature_spaces = [e.qsr_object_frame.qstag.graphlets]#, e.qsr_joints_frame.qstag.graphlets]

            for cnt, f in enumerate(feature_spaces):
                for freq, hash in zip(f.histogram, f.code_book):
                    try:
                        ind = np.where(global_codebook == hash)[0][0]
                        e.temp_histogram[ind] += freq
                    # If the hash doesn't exist in the global codebook yet - add it
                    except IndexError:
                        global_codebook = np.append(global_codebook, hash)
                        e.temp_histogram = np.append(e.temp_histogram, freq)
                        all_graphlets = np.append(all_graphlets, f.graphlets[hash])
                        # print "\n>", hash, f.graphlets[hash]

            # print global_codebook, e.temp_histogram, all_graphlets
            utils.save_event(e, "Learning/Histograms")

    print "Code book shape:", global_codebook.shape
    f = open(os.path.join(accu_path, "code_book_all.p"), "w")
    pickle.dump(global_codebook, f)
    f.close()

    f = open(os.path.join(accu_path, "graphlets_all.p"), "w")
    pickle.dump(all_graphlets, f)
    f.close()

    return global_codebook.shape[0]
def worker_padd(chunk):
    (event_file, histogram_directory) = chunk
    # print "    ", event_file
    e = utils.load_e(histogram_directory, event_file)

    # e.global_histogram = np.array([[0]*lenth_codebook])
    # ind = len(e.temp_histogram)

    #Overlay the global histogram with the temp histogram
    # e.global_histogram[0][:ind] = e.temp_histogram
    # utils.save_event(e)

    wordids = np.nonzero(e.temp_histogram)[0]
    # print "wordids:", type(wordids), wordids

    feature_counts = e.temp_histogram[wordids]
    # print "counts:", type(feature_counts), feature_counts

    if e.label != "NA":
        e.uuid += "_" + e.label

    rets = (wordids, feature_counts)
    # return (e.uuid, e.global_histogram[0])
    return (e.uuid, rets)
def worker_qsrs(chunk):
    (file_, path, config) = chunk
    #print "\n", path, file_
    e = utils.load_e(path, file_)

    dynamic_args = {}
    try:
        dynamic_args['argd'] = config['argd_args']
        dynamic_args['qtcbs'] = config['qtcbs_args']
        dynamic_args["qstag"] = {"params": config['qstag_args']}
        dynamic_args['filters'] = {
            "median_filter": {
                "window": config['qsr_mean_window']
            }
        }  # This has been updated since ECAI paper.
    except KeyError:
        print "check argd, qtcbs, qstag parameters in config file"

    joint_types = {
        'head': 'head',
        'torso': 'torso',
        'left_hand': 'hand',
        'right_hand': 'hand',
        'left_knee': 'knee',
        'right_knee': 'knee',
        'left_shoulder': 'shoulder',
        'right_shoulder': 'shoulder',
        'head-torso': 'tpcc-plane'
    }
    object_types = joint_types.copy()

    for ob, pos in e.objects.items():
        try:
            generic_object = "_".join(ob.split("_")[:-1])
            object_types[ob] = generic_object
            # print "object generic", generic_object
        except:
            print "didnt add:", object
    dynamic_args["qstag"]["object_types"] = object_types

    # for i,j in object_types.items():
    #     print ">", i,j
    """1. CREATE QSRs FOR joints & Object """
    qsrlib = QSRlib()
    qsrs_for = []
    for ob, pos in e.objects.items():
        qsrs_for.append((str(ob), 'left_hand'))
        qsrs_for.append((str(ob), 'right_hand'))
        qsrs_for.append((str(ob), 'torso'))
    dynamic_args['argd']["qsrs_for"] = qsrs_for
    dynamic_args['qtcbs']["qsrs_for"] = qsrs_for

    # for (i,j) in qsrs_for:
    #     print ">", (i,j)

    req = QSRlib_Request_Message(config['which_qsr'],
                                 input_data=e.map_world,
                                 dynamic_args=dynamic_args)
    e.qsr_object_frame = qsrlib.request_qsrs(req_msg=req)

    # print ">", e.qsr_object_frame.qstag.graphlets.histogram
    # for i in e.qsr_object_frame.qstag.episodes:
    #     print i
    # sys.exit(1)
    """2. CREATE QSRs for joints - TPCC"""
    # print "TPCC: ",
    # # e.qsr_joint_frame = get_joint_frame_qsrs(file, e.camera_world, joint_types, dynamic_args)
    # qsrs_for = [('head', 'torso', ob) if ob not in ['head', 'torso'] and ob != 'head-torso' else () for ob in joint_types.keys()]
    # dynamic_args['tpcc'] = {"qsrs_for": qsrs_for}
    # dynamic_args["qstag"]["params"] = {"min_rows": 1, "max_rows": 2, "max_eps": 4}
    # qsrlib = QSRlib()
    # req = QSRlib_Request_Message(which_qsr="tpcc", input_data=e.camera_world, dynamic_args=dynamic_args)
    # e.qsr_joints_frame = qsrlib.request_qsrs(req_msg=req)
    # # pretty_print_world_qsr_trace("tpcc", e.qsr_joints_frame)
    # # print e.qsr_joints_frame.qstag.graphlets.histogram
    utils.save_event(e, "Learning/QSR_Worlds")