The auction algorithm treats rows as “bidders” and columns as “objects”.
Each iteration, unassigned bidders bid for their most desirable objects,
and objects are assigned to the highest bidder.
This extends the basic assignment problem to allow tracks and
measurements to remain unassigned at a specified cost.
Parameters:
cost_matrix (array_like) – Cost matrix of shape (n_tracks, n_measurements).
cost_of_non_assignment (float, optional) – Cost for leaving a track or measurement unassigned.
If inf, all must be assigned (default: inf).
maximize (bool, optional) – If True, solve maximization problem (default: False).
Returns:
result – Named tuple containing:
- row_indices: Indices of assigned rows (tracks)
- col_indices: Indices of assigned columns (measurements)
- cost: Total assignment cost
- unassigned_rows: Indices of unassigned rows
- unassigned_cols: Indices of unassigned columns
Murty’s algorithm systematically partitions the solution space to
enumerate assignments in order of increasing cost. It is widely used
in Multiple Hypothesis Tracking (MHT) for hypothesis generation.
Parameters:
cost_matrix (array_like) – Cost matrix of shape (n_tracks, n_measurements).
cost_of_non_assignment (float, optional) – Cost for leaving a track or measurement unassigned.
If inf, all must be assigned (default: inf).
maximize (bool, optional) – If True, find k-best in descending order (default: False).
Returns:
result – Named tuple containing:
- assignments: List of k best AssignmentResult objects
- costs: Array of costs for each assignment
- n_found: Number of assignments actually found
cost_of_non_assignment (float, optional) – Cost for leaving a track or measurement unassigned.
maximize (bool, optional) – If True, find k-best in descending order.
cost_threshold (float, optional) – Stop when assignment cost exceeds this threshold (for minimization)
or falls below (for maximization). If None, no threshold.
Returns:
result – Named tuple containing assignments, costs, and count.
>>> cost=np.array([[10,5,13],[3,15,8],[12,7,9]])>>> result=kbest_assign2d(cost,k=10,cost_threshold=20)>>> result.n_found# Only assignments with cost <= 204
Notes
The cost threshold enables efficient pruning for MHT where hypotheses
with very low probability (high cost) can be discarded.
This function assumes all tracks must be assigned to measurements
(no non-assignment option). For track-oriented MHT with missed
detections, use kbest_assign2d with an appropriate
cost_of_non_assignment.
The 3D assignment problem is NP-hard, so all methods provide
approximate solutions. The Lagrangian relaxation method generally
provides the best quality with reasonable computation time.
This algorithm relaxes the 3D constraints and solves a sequence of
2D assignment problems. The Lagrange multipliers are updated using
subgradient optimization to improve the bound.
Parameters:
cost_tensor (array_like) – Cost tensor of shape (n1, n2, n3).
max_iter (int, optional) – Maximum number of iterations (default: 100).
tol (float, optional) – Convergence tolerance for gap (default: 1e-6).
The Lagrangian relaxation dualizes the constraint that each index
in the third dimension appears at most once. The resulting problem
decomposes into n3 independent 2D assignment problems.
The gap provides a measure of solution quality: gap = 0 indicates
an optimal solution.
The auction algorithm for 3D assignment alternates between phases:
1. Bidding phase: unassigned elements bid for their preferred matches
2. Assignment phase: matches are updated based on bids
This is a heuristic extension of the 2D auction algorithm and may
not find the global optimum.
This algorithm iteratively selects the lowest-cost unassigned tuple
until no more valid assignments can be made. It provides a fast but
suboptimal solution.
Parameters:
cost_tensor (array_like) – Cost tensor of shape (n1, n2, n3).
maximize (bool, optional) – If True, solve maximization problem (default: False).
Returns:
result – Assignment result with tuples, cost, and metadata.
Time complexity is O(n1 * n2 * n3 * min(n1, n2, n3)) in the worst case.
The greedy solution provides a starting point for more sophisticated
algorithms but is generally not optimal.
The algorithm iterates over the fixed dimension and solves a 2D
assignment for each slice. Indices that have been assigned in
previous slices are excluded from subsequent problems.
Time complexity is O(n * m^3) where n is the size of the fixed
dimension and m is the maximum of the other two dimensions.
The ellipsoidal gate defines a validation region based on the
chi-squared distribution of the squared Mahalanobis distance.
Parameters:
innovation (array_like) – Innovation vector of shape (m,).
innovation_covariance (array_like) – Innovation covariance matrix of shape (m, m).
gate_threshold (float) – Gate threshold (chi-squared value). Common values:
- 9.21 for 99% probability with 2 measurements
- 11.34 for 99% probability with 3 measurements
- 16.27 for 99% probability with 4 measurements
Returns:
True if measurement passes the gate (is inside the ellipsoid).
Finds the globally optimal assignment of tracks to measurements
that minimizes the total association cost.
Parameters:
cost_matrix (array_like) – Cost matrix of shape (n_tracks, n_measurements).
cost_matrix[i, j] is the cost of assigning track i to measurement j.
gate_threshold (float, optional) – Maximum cost for valid assignment. Entries above this threshold
are set to infinity before optimization.
cost_of_non_assignment (float, optional) – Cost for not assigning a track or measurement. If None, all
tracks/measurements that can be assigned will be assigned.
Returns:
result – Association result with track and measurement assignments.
GNN uses the Hungarian algorithm to find the globally optimal assignment.
It is more computationally expensive than nearest neighbor but guarantees
optimality.
The algorithm handles rectangular cost matrices (different numbers of
tracks and measurements) and allows tracks/measurements to remain
unassigned if cost_of_non_assignment is specified.
This is a greedy algorithm that processes tracks in order of their
minimum cost. It does not guarantee globally optimal assignment.
Use gnn_association for globally optimal assignment.
measurements (array_like) – Measurements of shape (n_measurements, n_meas).
measurement_models (array_like, optional) – Measurement matrices of shape (n_tracks, n_meas, n_state) or
(n_meas, n_state) if same for all tracks. If None, assumes
direct measurement of first n_meas states.
Returns:
cost_matrix – Cost matrix of shape (n_tracks, n_measurements).
cost_matrix[i, j] is the squared Mahalanobis distance from
track i to measurement j.
Return type:
ndarray
Examples
>>> # 2 tracks, 3 measurements, 2D state [x, vx]>>> predictions=np.array([[0.0,1.0],[5.0,-1.0]])>>> covariances=np.array([np.eye(2),np.eye(2)])>>> measurements=np.array([[0.1],[4.9],[10.0]])>>> H=np.array([[1.0,0.0]])# Measure position only>>> costs=compute_association_cost(predictions,covariances,measurements,H)
Association probability matrix of shape (n_tracks, n_measurements + 1).
association_probs[i, j] is the probability that track i is associated
with measurement j. The last column (j = n_measurements) represents
the probability that track i has no measurement.
Compute association probabilities for 2 tracks and 3 measurements:
>>> importnumpyasnp>>> # Two tracks with [x, vx] state>>> states=[np.array([0.0,1.0]),np.array([10.0,-0.5])]>>> covariances=[np.eye(2)*0.5,np.eye(2)*0.5]>>> # Three position measurements>>> measurements=np.array([[0.1],[9.8],[5.0]])>>> H=np.array([[1,0]])# measure position only>>> R=np.array([[0.1]])>>> result=jpda(states,covariances,measurements,H,R)>>> result.association_probs.shape# (2 tracks, 4 columns: 3 meas + miss)(2, 4)>>> # Track 0 should have high prob for measurement 0>>> result.association_probs[0,0]>0.5True
>>> importnumpyasnp>>> # Two tracks, three measurements>>> x1=np.array([0.,1.])# [position, velocity]>>> x2=np.array([5.,-1.])>>> P=np.eye(2)*0.1>>> measurements=np.array([[0.1],[5.2],[10.0]])>>> H=np.array([[1.,0.]])# Measure position>>> R=np.array([[0.1]])>>> result=jpda_update([x1,x2],[P,P],measurements,H,R)>>> len(result.states)2
Notes
The JPDA update consists of:
1. Compute measurement likelihoods and gating
2. Compute association probabilities
3. Compute combined innovations for each track
4. Update each track with weighted innovation
5. Compute covariance with spread of means term
detection_prob (float) – Probability of detection (Pd).
clutter_density (float) – Spatial density of clutter (lambda_c).
Returns:
beta – Association probability matrix, shape (n_tracks, n_meas + 1).
beta[i, j] = P(measurement j is from track i) for j < n_meas.
beta[i, n_meas] = P(track i has no measurement).
Return type:
ndarray[Any]
Examples
>>> importnumpyasnp>>> # Likelihood matrix: 2 tracks, 2 measurements>>> # Track 0 has high likelihood for meas 0>>> # Track 1 has high likelihood for meas 1>>> likelihood=np.array([[0.9,0.1],... [0.1,0.8]])>>> gated=np.array([[True,True],... [True,True]])>>> beta=jpda_probabilities(likelihood,gated,detection_prob=0.9)>>> beta.shape# 2 tracks, 3 columns (2 meas + 1 miss)(2, 3)>>> # Track 0 most likely associated with measurement 0>>> np.argmax(beta[0,:2])0
>>> importnumpyasnp>>> # Two tracks, two measurements>>> states=[np.array([0.0,1.0]),np.array([5.0,0.0])]>>> covs=[np.eye(2)*0.5,np.eye(2)*0.5]>>> measurements=np.array([[0.1],[5.2]])>>> H=np.array([[1,0]])>>> R=np.array([[0.1]])>>> L,gated=compute_likelihood_matrix(states,covs,measurements,H,R)>>> L.shape(2, 2)>>> # Track 0 should have high likelihood for measurement 0>>> L[0,0]>L[0,1]True
The relaxation approach:
1. Maintain Lagrange multipliers for each dimension
2. Solve relaxed problem (select best entries per tuple)
3. Update multipliers based on constraint violations
4. Iterate until convergence or gap tolerance met
This guarantees a lower bound on optimal cost and often finds
near-optimal or optimal solutions.
>>> importnumpyasnp>>> # 4D assignment: sensors x measurements x tracks x hypotheses>>> np.random.seed(123)>>> cost=np.random.rand(2,3,3,2)*10>>> result=auction_assignment_nd(cost,max_iterations=50,epsilon=0.1)>>> len(result.assignments)>0True>>> result.n_iterations<=50True
Notes
The algorithm maintains a “price” for each index and allows bidding
(price adjustment) to maximize value. Converges to epsilon-optimal
solution in finite iterations.
>>> importnumpyasnp>>> # Valid assignment: no index repeated in any dimension>>> assignments=np.array([[0,0],[1,1]])>>> detect_dimension_conflicts(assignments,(3,3))False>>> # Invalid: index 0 used twice in first dimension>>> assignments=np.array([[0,0],[0,1]])>>> detect_dimension_conflicts(assignments,(3,3))True
Convert 2D assignment problem to min-cost flow network.
Network structure:
- Source node (0) supplies all workers
- Worker nodes (1 to m) demand 1 unit each
- Task nodes (m+1 to m+n) supply 1 unit each
- Sink node (m+n+1) collects all completed tasks
Parameters:
cost_matrix (ndarray) – Cost matrix of shape (m, n) where cost[i,j] is cost of
assigning worker i to task j.
Returns:
edges (list[FlowEdge]) – List of edges in the flow network.
supplies (ndarray) – Supply/demand at each node (shape n_nodes,).
Positive = supply, negative = demand.
node_names (ndarray) – Names of nodes for reference.
Solve min-cost flow using successive shortest paths with cost scaling.
Algorithm:
1. Initialize potentials using Bellman-Ford
2. While there is excess supply:
Find shortest path using reduced costs (Dijkstra with potentials)
Push unit flow along path
Update node potentials
Recompute shortest paths to maintain optimality
This is the standard min-cost flow algorithm that guarantees optimality
and convergence. It uses Dijkstra’s algorithm with potentials, which
maintains the dual feasibility (reduced cost property).
Parameters:
edges (list[FlowEdge]) – List of edges with capacities and costs.
supplies (ndarray) – Supply/demand at each node.
max_iterations (int, optional) – Maximum iterations (default 1000).
Returns:
Solution with flow values, cost, status, and iterations.
This implementation uses successive shortest paths with potentials.
The algorithm is guaranteed to find the optimal solution for any
feasible min-cost flow problem.
For rectangular assignment problems (m < n or m > n), all m units
of flow must be satisfied. The algorithm ensures this by finding
augmenting paths until all supply is routed.
The ellipsoidal gate defines a validation region based on the
chi-squared distribution of the squared Mahalanobis distance.
Parameters:
innovation (array_like) – Innovation vector of shape (m,).
innovation_covariance (array_like) – Innovation covariance matrix of shape (m, m).
gate_threshold (float) – Gate threshold (chi-squared value). Common values:
- 9.21 for 99% probability with 2 measurements
- 11.34 for 99% probability with 3 measurements
- 16.27 for 99% probability with 4 measurements
Returns:
True if measurement passes the gate (is inside the ellipsoid).
measurements (array_like) – Measurements of shape (n_measurements, n_meas).
measurement_models (array_like, optional) – Measurement matrices of shape (n_tracks, n_meas, n_state) or
(n_meas, n_state) if same for all tracks. If None, assumes
direct measurement of first n_meas states.
Returns:
cost_matrix – Cost matrix of shape (n_tracks, n_measurements).
cost_matrix[i, j] is the squared Mahalanobis distance from
track i to measurement j.
Return type:
ndarray
Examples
>>> # 2 tracks, 3 measurements, 2D state [x, vx]>>> predictions=np.array([[0.0,1.0],[5.0,-1.0]])>>> covariances=np.array([np.eye(2),np.eye(2)])>>> measurements=np.array([[0.1],[4.9],[10.0]])>>> H=np.array([[1.0,0.0]])# Measure position only>>> costs=compute_association_cost(predictions,covariances,measurements,H)
This is a greedy algorithm that processes tracks in order of their
minimum cost. It does not guarantee globally optimal assignment.
Use gnn_association for globally optimal assignment.
Finds the globally optimal assignment of tracks to measurements
that minimizes the total association cost.
Parameters:
cost_matrix (array_like) – Cost matrix of shape (n_tracks, n_measurements).
cost_matrix[i, j] is the cost of assigning track i to measurement j.
gate_threshold (float, optional) – Maximum cost for valid assignment. Entries above this threshold
are set to infinity before optimization.
cost_of_non_assignment (float, optional) – Cost for not assigning a track or measurement. If None, all
tracks/measurements that can be assigned will be assigned.
Returns:
result – Association result with track and measurement assignments.
GNN uses the Hungarian algorithm to find the globally optimal assignment.
It is more computationally expensive than nearest neighbor but guarantees
optimality.
The algorithm handles rectangular cost matrices (different numbers of
tracks and measurements) and allows tracks/measurements to remain
unassigned if cost_of_non_assignment is specified.
The JPDA algorithm computes association probabilities for all feasible
track-measurement pairings and updates each track with a weighted combination
of innovations.
Joint Probabilistic Data Association (JPDA) algorithm.
JPDA computes association probabilities between tracks and measurements
by considering all possible joint association hypotheses, then performs
a probabilistically weighted update for each track.
This is more sophisticated than GNN which makes hard assignment decisions,
as JPDA can handle measurement origin uncertainty in cluttered environments.
Association probability matrix of shape (n_tracks, n_measurements + 1).
association_probs[i, j] is the probability that track i is associated
with measurement j. The last column (j = n_measurements) represents
the probability that track i has no measurement.
>>> importnumpyasnp>>> # Two tracks, two measurements>>> states=[np.array([0.0,1.0]),np.array([5.0,0.0])]>>> covs=[np.eye(2)*0.5,np.eye(2)*0.5]>>> measurements=np.array([[0.1],[5.2]])>>> H=np.array([[1,0]])>>> R=np.array([[0.1]])>>> L,gated=compute_likelihood_matrix(states,covs,measurements,H,R)>>> L.shape(2, 2)>>> # Track 0 should have high likelihood for measurement 0>>> L[0,0]>L[0,1]True
detection_prob (float) – Probability of detection (Pd).
clutter_density (float) – Spatial density of clutter (lambda_c).
Returns:
beta – Association probability matrix, shape (n_tracks, n_meas + 1).
beta[i, j] = P(measurement j is from track i) for j < n_meas.
beta[i, n_meas] = P(track i has no measurement).
Return type:
ndarray[Any]
Examples
>>> importnumpyasnp>>> # Likelihood matrix: 2 tracks, 2 measurements>>> # Track 0 has high likelihood for meas 0>>> # Track 1 has high likelihood for meas 1>>> likelihood=np.array([[0.9,0.1],... [0.1,0.8]])>>> gated=np.array([[True,True],... [True,True]])>>> beta=jpda_probabilities(likelihood,gated,detection_prob=0.9)>>> beta.shape# 2 tracks, 3 columns (2 meas + 1 miss)(2, 3)>>> # Track 0 most likely associated with measurement 0>>> np.argmax(beta[0,:2])0
>>> importnumpyasnp>>> # Two tracks, three measurements>>> x1=np.array([0.,1.])# [position, velocity]>>> x2=np.array([5.,-1.])>>> P=np.eye(2)*0.1>>> measurements=np.array([[0.1],[5.2],[10.0]])>>> H=np.array([[1.,0.]])# Measure position>>> R=np.array([[0.1]])>>> result=jpda_update([x1,x2],[P,P],measurements,H,R)>>> len(result.states)2
Notes
The JPDA update consists of:
1. Compute measurement likelihoods and gating
2. Compute association probabilities
3. Compute combined innovations for each track
4. Update each track with weighted innovation
5. Compute covariance with spread of means term
Compute association probabilities for 2 tracks and 3 measurements:
>>> importnumpyasnp>>> # Two tracks with [x, vx] state>>> states=[np.array([0.0,1.0]),np.array([10.0,-0.5])]>>> covariances=[np.eye(2)*0.5,np.eye(2)*0.5]>>> # Three position measurements>>> measurements=np.array([[0.1],[9.8],[5.0]])>>> H=np.array([[1,0]])# measure position only>>> R=np.array([[0.1]])>>> result=jpda(states,covariances,measurements,H,R)>>> result.association_probs.shape# (2 tracks, 4 columns: 3 meas + miss)(2, 4)>>> # Track 0 should have high prob for measurement 0>>> result.association_probs[0,0]>0.5True