tracker.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 kalman_filter
00005 from . import linear_assignment
00006 from . import iou_matching
00007 from .track import Track
00008 
00009 
00010 class Tracker:
00011     """
00012     This is the multi-target tracker.
00013 
00014     Parameters
00015     ----------
00016     metric : nn_matching.NearestNeighborDistanceMetric
00017         A distance metric for measurement-to-track association.
00018     max_age : int
00019         Maximum number of missed misses before a track is deleted.
00020     n_init : int
00021         Number of consecutive detections before the track is confirmed. The
00022         track state is set to `Deleted` if a miss occurs within the first
00023         `n_init` frames.
00024 
00025     Attributes
00026     ----------
00027     metric : nn_matching.NearestNeighborDistanceMetric
00028         The distance metric used for measurement to track association.
00029     max_age : int
00030         Maximum number of missed misses before a track is deleted.
00031     n_init : int
00032         Number of frames that a track remains in initialization phase.
00033     kf : kalman_filter.KalmanFilter
00034         A Kalman filter to filter target trajectories in image space.
00035     tracks : List[Track]
00036         The list of active tracks at the current time step.
00037 
00038     """
00039 
00040     def __init__(self, metric, max_iou_distance=0.7, max_age=30, n_init=3):
00041         self.metric = metric
00042         self.max_iou_distance = max_iou_distance
00043         self.max_age = max_age
00044         self.n_init = n_init
00045 
00046         self.kf = kalman_filter.KalmanFilter()
00047         self.tracks = []
00048         self._next_id = 1
00049 
00050     def predict(self):
00051         """Propagate track state distributions one time step forward.
00052 
00053         This function should be called once every time step, before `update`.
00054         """
00055         for track in self.tracks:
00056             track.predict(self.kf)
00057 
00058     def update(self, detections):
00059         """Perform measurement update and track management.
00060 
00061         Parameters
00062         ----------
00063         detections : List[deep_sort.detection.Detection]
00064             A list of detections at the current time step.
00065 
00066         """
00067         # Run matching cascade.
00068         matches, unmatched_tracks, unmatched_detections = \
00069             self._match(detections)
00070 
00071         # Update track set.
00072         for track_idx, detection_idx in matches:
00073             self.tracks[track_idx].update(
00074                 self.kf, detections[detection_idx])
00075         for track_idx in unmatched_tracks:
00076             self.tracks[track_idx].mark_missed()
00077         for detection_idx in unmatched_detections:
00078             self._initiate_track(detections[detection_idx])
00079         self.tracks = [t for t in self.tracks if not t.is_deleted()]
00080 
00081         # Update distance metric.
00082         active_targets = [t.track_id for t in self.tracks if t.is_confirmed()]
00083         features, targets = [], []
00084         for track in self.tracks:
00085             if not track.is_confirmed():
00086                 continue
00087             features += track.features
00088             targets += [track.track_id for _ in track.features]
00089             track.features = []
00090         self.metric.partial_fit(
00091             np.asarray(features), np.asarray(targets), active_targets)
00092 
00093     def _match(self, detections):
00094 
00095         def gated_metric(tracks, dets, track_indices, detection_indices):
00096             features = np.array([dets[i].feature for i in detection_indices])
00097             targets = np.array([tracks[i].track_id for i in track_indices])
00098             cost_matrix = self.metric.distance(features, targets)
00099             cost_matrix = linear_assignment.gate_cost_matrix(
00100                 self.kf, cost_matrix, tracks, dets, track_indices,
00101                 detection_indices)
00102 
00103             return cost_matrix
00104 
00105         # Split track set into confirmed and unconfirmed tracks.
00106         confirmed_tracks = [
00107             i for i, t in enumerate(self.tracks) if t.is_confirmed()]
00108         unconfirmed_tracks = [
00109             i for i, t in enumerate(self.tracks) if not t.is_confirmed()]
00110 
00111         # Associate confirmed tracks using appearance features.
00112         matches_a, unmatched_tracks_a, unmatched_detections = \
00113             linear_assignment.matching_cascade(
00114                 gated_metric, self.metric.matching_threshold, self.max_age,
00115                 self.tracks, detections, confirmed_tracks)
00116 
00117         # Associate remaining tracks together with unconfirmed tracks using IOU.
00118         iou_track_candidates = unconfirmed_tracks + [
00119             k for k in unmatched_tracks_a if
00120             self.tracks[k].time_since_update == 1]
00121         unmatched_tracks_a = [
00122             k for k in unmatched_tracks_a if
00123             self.tracks[k].time_since_update != 1]
00124         matches_b, unmatched_tracks_b, unmatched_detections = \
00125             linear_assignment.min_cost_matching(
00126                 iou_matching.iou_cost, self.max_iou_distance, self.tracks,
00127                 detections, iou_track_candidates, unmatched_detections)
00128 
00129         matches = matches_a + matches_b
00130         unmatched_tracks = list(set(unmatched_tracks_a + unmatched_tracks_b))
00131         return matches, unmatched_tracks, unmatched_detections
00132 
00133     def _initiate_track(self, detection):
00134         mean, covariance = self.kf.initiate(detection.to_xyah())
00135         self.tracks.append(Track(
00136             mean, covariance, self._next_id, self.n_init, self.max_age,
00137             detection.feature))
00138         self._next_id += 1


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