iou_matching.py
Go to the documentation of this file.
00001 # vim: expandtab:ts=4:sw=4
00002 from __future__ import absolute_import
00003 import numpy as np
00004 from . import linear_assignment
00005 
00006 
00007 def iou(bbox, candidates):
00008     """Computer intersection over union.
00009 
00010     Parameters
00011     ----------
00012     bbox : ndarray
00013         A bounding box in format `(top left x, top left y, width, height)`.
00014     candidates : ndarray
00015         A matrix of candidate bounding boxes (one per row) in the same format
00016         as `bbox`.
00017 
00018     Returns
00019     -------
00020     ndarray
00021         The intersection over union in [0, 1] between the `bbox` and each
00022         candidate. A higher score means a larger fraction of the `bbox` is
00023         occluded by the candidate.
00024 
00025     """
00026     bbox_tl, bbox_br = bbox[:2], bbox[:2] + bbox[2:]
00027     candidates_tl = candidates[:, :2]
00028     candidates_br = candidates[:, :2] + candidates[:, 2:]
00029 
00030     tl = np.c_[np.maximum(bbox_tl[0], candidates_tl[:, 0])[:, np.newaxis],
00031                np.maximum(bbox_tl[1], candidates_tl[:, 1])[:, np.newaxis]]
00032     br = np.c_[np.minimum(bbox_br[0], candidates_br[:, 0])[:, np.newaxis],
00033                np.minimum(bbox_br[1], candidates_br[:, 1])[:, np.newaxis]]
00034     wh = np.maximum(0., br - tl)
00035 
00036     area_intersection = wh.prod(axis=1)
00037     area_bbox = bbox[2:].prod()
00038     area_candidates = candidates[:, 2:].prod(axis=1)
00039     return area_intersection / (area_bbox + area_candidates - area_intersection)
00040 
00041 
00042 def iou_cost(tracks, detections, track_indices=None,
00043              detection_indices=None):
00044     """An intersection over union distance metric.
00045 
00046     Parameters
00047     ----------
00048     tracks : List[deep_sort.track.Track]
00049         A list of tracks.
00050     detections : List[deep_sort.detection.Detection]
00051         A list of detections.
00052     track_indices : Optional[List[int]]
00053         A list of indices to tracks that should be matched. Defaults to
00054         all `tracks`.
00055     detection_indices : Optional[List[int]]
00056         A list of indices to detections that should be matched. Defaults
00057         to all `detections`.
00058 
00059     Returns
00060     -------
00061     ndarray
00062         Returns a cost matrix of shape
00063         len(track_indices), len(detection_indices) where entry (i, j) is
00064         `1 - iou(tracks[track_indices[i]], detections[detection_indices[j]])`.
00065 
00066     """
00067     if track_indices is None:
00068         track_indices = np.arange(len(tracks))
00069     if detection_indices is None:
00070         detection_indices = np.arange(len(detections))
00071 
00072     cost_matrix = np.zeros((len(track_indices), len(detection_indices)))
00073     for row, track_idx in enumerate(track_indices):
00074         if tracks[track_idx].time_since_update > 1:
00075             cost_matrix[row, :] = linear_assignment.INFTY_COST
00076             continue
00077 
00078         bbox = tracks[track_idx].to_tlwh()
00079         candidates = np.asarray([detections[i].tlwh for i in detection_indices])
00080         cost_matrix[row, :] = 1. - iou(bbox, candidates)
00081     return cost_matrix


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07