Apollo  6.0
Open source self driving car software
hungarian_optimizer.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 
17 #pragma once
18 
19 #include <algorithm>
20 #include <limits>
21 #include <utility>
22 #include <vector>
23 
24 #include "Eigen/Dense"
25 
27 
28 namespace apollo {
29 namespace perception {
30 namespace common {
31 
32 template <typename T>
34  static const int kHungarianOptimizerRowNotFound = -1;
35  static const int kHungarianOptimizerColNotFound = -2;
36 
37  public:
38  /* Setup the initial conditions for the algorithm. */
40  explicit HungarianOptimizer(const int max_optimization_size);
42 
43  SecureMat<T>* costs() { return &costs_; }
44 
45  T* costs(const size_t row, const size_t col) { return &(costs_(row, col)); }
46 
47  void Maximize(std::vector<std::pair<size_t, size_t>>* assignments);
48  void Minimize(std::vector<std::pair<size_t, size_t>>* assignments);
49 
50  void OptimizationInit();
51  void OptimizationClear();
52 
53  /* Print the matrix to stdout (for debugging.) */
54  void PrintMatrix();
55 
56  private:
57  enum class Mark { NONE, PRIME, STAR };
58 
59  /* Convert the final cost matrix into a set of assignments of agents to tasks.
60  * Return the assignment in a vector of pair, the same as Minimize() and
61  * Maximize() */
62  void FindAssignments(std::vector<std::pair<size_t, size_t>>* assignments);
63 
64  /* Is the cell (row, col) starred? */
65  bool IsStarred(const size_t row, const size_t col) const {
66  return marks_(row, col) == Mark::STAR;
67  }
68 
69  /* Mark cell (row, col) with a star */
70  void Star(const size_t row, const size_t col) {
71  marks_(row, col) = Mark::STAR;
72  ++stars_in_col_[col];
73  }
74 
75  /* Remove a star from cell (row, col) */
76  void Unstar(const size_t row, const size_t col) {
77  marks_(row, col) = Mark::NONE;
78  --stars_in_col_[col];
79  }
80 
81  /* Find a column in row 'row' containing a star, or return
82  * kHungarianOptimizerColNotFound if no such column exists. */
83  int FindStarInRow(const size_t row) const;
84 
85  /* Find a row in column 'col' containing a star, or return
86  * kHungarianOptimizerRowNotFound if no such row exists. */
87  int FindStarInCol(const size_t col) const;
88 
89  /* Is cell (row, col) marked with a prime? */
90  bool IsPrimed(const size_t row, const size_t col) const {
91  return marks_(row, col) == Mark::PRIME;
92  }
93 
94  /* Mark cell (row, col) with a prime. */
95  void Prime(const size_t row, const size_t col) {
96  marks_(row, col) = Mark::PRIME;
97  }
98 
99  /* Find a column in row containing a prime, or return
100  * kHungarianOptimizerColNotFound if no such column exists. */
101  int FindPrimeInRow(const size_t row) const;
102 
103  /* Remove the prime marks_ from every cell in the matrix. */
104  void ClearPrimes();
105 
106  /* Does column col contain a star? */
107  bool ColContainsStar(const size_t col) const {
108  return stars_in_col_[col] > 0;
109  }
110 
111  /* Is row 'row' covered? */
112  bool RowCovered(const size_t row) const { return rows_covered_[row]; }
113 
114  /* Cover row 'row'. */
115  void CoverRow(const size_t row) { rows_covered_[row] = true; }
116 
117  /* Uncover row 'row'. */
118  void UncoverRow(const size_t row) { rows_covered_[row] = false; }
119 
120  /* Is column col covered? */
121  bool ColCovered(const size_t col) const { return cols_covered_[col]; }
122 
123  /* Cover column col. */
124  void CoverCol(const size_t col) { cols_covered_[col] = true; }
125 
126  /* Uncover column col. */
127  void UncoverCol(const size_t col) { cols_covered_[col] = false; }
128 
129  /* Uncover ever row and column in the matrix. */
130  void ClearCovers();
131 
132  /* Find the smallest uncovered cell in the matrix. */
133  T FindSmallestUncovered();
134 
135  /* Find an uncovered zero and store its coordinates in (zeroRow_, zeroCol_)
136  * and return true, or return false if no such cell exists. */
137  bool FindZero(size_t* zero_row, size_t* zero_col);
138 
139  /* Run the Munkres algorithm! */
140  void DoMunkres();
141 
142  void CheckStar();
143 
144  /* Step 1:
145  * For each row of the matrix, find the smallest element and subtract it from
146  * every element in its row. Go to Step 2. */
147  void ReduceRows();
148 
149  /* Step 2:
150  * Find a zero (Z) in the matrix. If there is no starred zero in its row or
151  * column, star Z. Repeat for every element in the matrix. Go to Step 3.
152  * Note: profiling shows this method to use 9.2% of the CPU - the next
153  * slowest step takes 0.6%. It is hard to find a way further speed it up. */
154  void StarZeroes();
155 
156  /* Step 3:
157  * Cover each column containing a starred zero. If all columns are covered,
158  * the starred zeros describe a complete set of unique assignments.
159  * In this case, terminate the algorithm. Otherwise, go to Step 4. */
160  void CoverStarredZeroes();
161 
162  /* Step 4:
163  * Find a noncovered zero and prime it. If there is no starred zero in the
164  * row containing this primed zero, Go to Step 5. Otherwise, cover this row
165  * and uncover the column containing the starred zero. Continue in this manner
166  * until there are no uncovered zeros left, then go to Step 6. */
167  void PrimeZeroes();
168 
169  /* Step 5:
170  * Construct a series of alternating primed and starred zeros as follows.
171  * Let Z0 represent the uncovered primed zero found in Step 4. Let Z1 denote
172  * the starred zero in the column of Z0 (if any). Let Z2 denote the primed
173  * zero in the row of Z1 (there will always be one). Continue until the
174  * series terminates at a primed zero that has no starred zero in its column.
175  * Unstar each starred zero of the series, star each primed zero of the
176  * series, erase all primes and uncover every line in the matrix. Return to
177  * Step 3. */
178  void MakeAugmentingPath();
179 
180  /* Step 6:
181  * Add the smallest uncovered value in the matrix to every element of each
182  * covered row, and subtract it from every element of each uncovered column.
183  * Return to Step 4 without altering any stars, primes, or covered lines. */
184  void AugmentPath();
185 
186  /* the max optimization size set to control memory */
187  int max_optimization_size_ = 1000;
188 
189  /* status of optimization initialization */
190  bool optimization_initialized_ = false;
191 
192  /* the size of the problem, i.e. std::max(#agents, #tasks). */
193  size_t matrix_size_ = 0;
194 
195  /* the expanded cost matrix. */
196  SecureMat<T> costs_;
197 
198  /* the greatest cost in the initial cost matrix. */
199  T max_cost_{0};
200 
201  /* which rows and columns are currently covered. */
202  std::vector<bool> rows_covered_;
203  std::vector<bool> cols_covered_;
204 
205  /* the marks (star/prime/none) on each element of the cost matrix. */
206  SecureMat<Mark> marks_;
207 
208  /* the number of stars in each column - used to speed up coverStarredZeroes.*/
209  std::vector<int> stars_in_col_;
210 
211  /* representation of a path_ through the matrix - used in Step 5. */
212  std::vector<std::pair<size_t, size_t>> assignments_;
213 
214  /* the locations of a zero found in Step 4. */
215  int zero_col_ = 0;
216  int zero_row_ = 0;
217 
218  /* the width_ and height_ of the initial (non-expanded) cost matrix. */
219  size_t width_ = 0;
220  size_t height_ = 0;
221 
222  /* The current state of the algorithm */
223  std::function<void()> fn_state_ = nullptr;
224 
225  std::vector<size_t> uncov_col_;
226  std::vector<size_t> uncov_row_;
227 }; // class HungarianOptimizer
228 
229 template <typename T>
231 
232 template <typename T>
233 HungarianOptimizer<T>::HungarianOptimizer(const int max_optimization_size)
234  : max_optimization_size_(max_optimization_size) {
235  costs_.Reserve(max_optimization_size, max_optimization_size);
236  stars_in_col_.reserve(max_optimization_size);
237  rows_covered_.reserve(max_optimization_size);
238  cols_covered_.reserve(max_optimization_size);
239  assignments_.reserve(max_optimization_size);
240  uncov_row_.reserve(max_optimization_size);
241  uncov_col_.reserve(max_optimization_size);
242 }
243 
244 /* Find an assignment which maximizes the overall costs.
245  * Return an array of pairs of integers. Each pair (i, j) corresponds to
246  * assigning agent i to task j. */
247 template <typename T>
249  std::vector<std::pair<size_t, size_t>>* assignments) {
250  OptimizationInit();
251  /* operate maximizing problem as a minimizing one via substrating original
252  * cost from max_cost_ */
253  for (size_t row = 0; row < height_; ++row) {
254  for (size_t col = 0; col < width_; ++col) {
255  costs_(row, col) = max_cost_ - costs_(row, col);
256  }
257  }
258  Minimize(assignments);
259 }
260 
261 /* Find an assignment which minimizes the overall costs.
262  * Return an array of pairs of integers. Each pair (i, j) corresponds to
263  * assigning agent i to task j. */
264 template <typename T>
266  std::vector<std::pair<size_t, size_t>>* assignments) {
267  OptimizationInit();
268  DoMunkres();
269  FindAssignments(assignments);
270  OptimizationClear();
271 }
272 
273 template <typename T>
275  if (optimization_initialized_) {
276  return;
277  }
278  width_ = costs_.width();
279  if (width_ > 0) {
280  height_ = costs_.height();
281  } else {
282  height_ = 0;
283  }
284 
285  matrix_size_ = std::max(height_, width_);
286  max_cost_ = 0;
287 
288  /* generate the expanded cost matrix by adding extra 0s in order to make a
289  * square matrix. Meanwhile, find the max cost in the matrix. It may be used
290  * later, if we want to maximizing rather than minimizing the overall costs.*/
291  costs_.Resize(matrix_size_, matrix_size_);
292  for (size_t row = 0; row < matrix_size_; ++row) {
293  for (size_t col = 0; col < matrix_size_; ++col) {
294  if ((row >= height_) || (col >= width_)) {
295  costs_(row, col) = 0;
296  } else {
297  max_cost_ = std::max(max_cost_, costs_(row, col));
298  }
299  }
300  }
301 
302  /* initially, none of the cells of the matrix are marked. */
303  marks_.Resize(matrix_size_, matrix_size_);
304  for (size_t row = 0; row < matrix_size_; ++row) {
305  for (size_t col = 0; col < matrix_size_; ++col) {
306  marks_(row, col) = Mark::NONE;
307  }
308  }
309 
310  stars_in_col_.assign(matrix_size_, 0);
311 
312  rows_covered_.assign(matrix_size_, false);
313  cols_covered_.assign(matrix_size_, false);
314 
315  assignments_.resize(matrix_size_ * 2);
316 
317  optimization_initialized_ = true;
318 }
319 
320 template <typename T>
322  optimization_initialized_ = false;
323 }
324 
325 /* Convert the final costs matrix into a set of assignments of agents to tasks.
326  * Return an array of pairs of integers, the same as the return values of
327  * Minimize() and Maximize() */
328 template <typename T>
330  std::vector<std::pair<size_t, size_t>>* assignments) {
331  assignments->clear();
332  for (size_t row = 0; row < height_; ++row) {
333  for (size_t col = 0; col < width_; ++col) {
334  if (IsStarred(row, col)) {
335  assignments->push_back(std::make_pair(row, col));
336  break;
337  }
338  }
339  }
340 }
341 
342 /* Find a column in row 'row' containing a star, or return
343  * kHungarianOptimizerColNotFound if no such column exists. */
344 template <typename T>
345 int HungarianOptimizer<T>::FindStarInRow(const size_t row) const {
346  for (size_t col = 0; col < matrix_size_; ++col) {
347  if (IsStarred(row, col)) {
348  return static_cast<int>(col);
349  }
350  }
351 
352  return kHungarianOptimizerColNotFound;
353 }
354 
355 /* Find a row in column 'col' containing a star, or return
356  * kHungarianOptimizerRowNotFound if no such row exists. */
357 template <typename T>
358 int HungarianOptimizer<T>::FindStarInCol(const size_t col) const {
359  if (!ColContainsStar(col)) {
360  return kHungarianOptimizerRowNotFound;
361  }
362 
363  for (size_t row = 0; row < matrix_size_; ++row) {
364  if (IsStarred(row, col)) {
365  return static_cast<int>(row);
366  }
367  }
368 
369  // NOT REACHED
370  return kHungarianOptimizerRowNotFound;
371 }
372 
373 /* Find a column in row containing a prime, or return
374  * kHungarianOptimizerColNotFound if no such column exists. */
375 template <typename T>
376 int HungarianOptimizer<T>::FindPrimeInRow(const size_t row) const {
377  for (size_t col = 0; col < matrix_size_; ++col) {
378  if (IsPrimed(row, col)) {
379  return static_cast<int>(col);
380  }
381  }
382 
383  return kHungarianOptimizerColNotFound;
384 }
385 
386 /* Remove the prime marks from every cell in the matrix. */
387 template <typename T>
389  for (size_t row = 0; row < matrix_size_; ++row) {
390  for (size_t col = 0; col < matrix_size_; ++col) {
391  if (IsPrimed(row, col)) {
392  marks_(row, col) = Mark::NONE;
393  }
394  }
395  }
396 }
397 
398 /* Uncover every row and column in the matrix. */
399 template <typename T>
401  for (size_t x = 0; x < matrix_size_; x++) {
402  UncoverRow(x);
403  UncoverCol(x);
404  }
405 }
406 
407 /* Find the smallest uncovered cell in the matrix. */
408 template <typename T>
410  T minval = std::numeric_limits<T>::max();
411  uncov_col_.clear();
412  uncov_row_.clear();
413 
414  for (size_t i = 0; i < matrix_size_; ++i) {
415  if (!RowCovered(i)) {
416  uncov_row_.push_back(i);
417  }
418  if (!ColCovered(i)) {
419  uncov_col_.push_back(i);
420  }
421  }
422 
423  for (size_t row = 0; row < uncov_row_.size(); ++row) {
424  for (size_t col = 0; col < uncov_col_.size(); ++col) {
425  minval = std::min(minval, costs_(uncov_row_[row], uncov_col_[col]));
426  }
427  }
428 
429  return minval;
430 }
431 
432 /* Find an uncovered zero and store its coordinates in (zeroRow, zeroCol)
433  * and return true, or return false if no such cell exists. */
434 template <typename T>
435 bool HungarianOptimizer<T>::FindZero(size_t* zero_row, size_t* zero_col) {
436  uncov_col_.clear();
437  uncov_row_.clear();
438 
439  for (size_t i = 0; i < matrix_size_; ++i) {
440  if (!RowCovered(i)) {
441  uncov_row_.push_back(i);
442  }
443  if (!ColCovered(i)) {
444  uncov_col_.push_back(i);
445  }
446  }
447  if (uncov_row_.empty() || uncov_col_.empty()) {
448  return false;
449  }
450 
451  for (size_t i = 0; i < uncov_row_.size(); ++i) {
452  for (size_t j = 0; j < uncov_col_.size(); ++j) {
453  if (costs_(uncov_row_[i], uncov_col_[j]) == 0) {
454  *zero_row = uncov_row_[i];
455  *zero_col = uncov_col_[j];
456  return true;
457  }
458  }
459  }
460  return false;
461 }
462 
463 /* Print the matrix to stdout (for debugging). */
464 template <typename T>
466  for (size_t row = 0; row < matrix_size_; ++row) {
467  for (size_t col = 0; col < matrix_size_; ++col) {
468  printf("%g ", costs_(row, col));
469 
470  if (IsStarred(row, col)) {
471  printf("*");
472  }
473 
474  if (IsPrimed(row, col)) {
475  printf("'");
476  }
477  }
478  printf("\n");
479  }
480 }
481 
482 /* Run the Munkres algorithm */
483 template <typename T>
485  int max_num_iter = 1000;
486  int num_iter = 0;
487  fn_state_ = std::bind(&HungarianOptimizer::ReduceRows, this);
488  while (fn_state_ != nullptr && num_iter < max_num_iter) {
489  fn_state_();
490  ++num_iter;
491  }
492  if (num_iter >= max_num_iter) {
493  CheckStar();
494  }
495 }
496 
497 template <typename T>
499  for (size_t row = 0; row < height_; ++row) {
500  int star_col = -1;
501  bool is_single = true;
502  for (size_t col = 0; col < width_; ++col) {
503  if (IsStarred(row, col)) {
504  if (star_col == -1) {
505  star_col = col;
506  } else {
507  is_single = false;
508  break;
509  }
510  }
511  }
512  if (!is_single) {
513  for (size_t col = 0; col < width_; ++col) {
514  Unstar(row, col);
515  }
516  }
517  }
518 }
519 
520 /* Step 1:
521  * For each row of the matrix, find the smallest element and substract it
522  * from every element in its row. Then, go to Step 2. */
523 template <typename T>
525  for (size_t row = 0; row < matrix_size_; ++row) {
526  T min_cost = costs_(row, 0);
527  for (size_t col = 1; col < matrix_size_; ++col) {
528  min_cost = std::min(min_cost, costs_(row, col));
529  }
530  for (size_t col = 0; col < matrix_size_; ++col) {
531  costs_(row, col) -= min_cost;
532  }
533  }
534  fn_state_ = std::bind(&HungarianOptimizer::StarZeroes, this);
535 }
536 
537 /* Step 2:
538  * Find a zero Z in the matrix. If there is no starred zero in its row
539  * or column, star Z. Repeat for every element in the matrix. Then, go to
540  * Step3. */
541 template <typename T>
543  /* since no rows or columns are covered on entry to this step, we use the
544  * covers as a quick way of making which rows & columns have stars in them */
545  for (size_t row = 0; row < matrix_size_; ++row) {
546  if (RowCovered(row)) {
547  continue;
548  }
549  for (size_t col = 0; col < matrix_size_; ++col) {
550  if (ColCovered(col)) {
551  continue;
552  }
553  if (costs_(row, col) == 0) {
554  Star(row, col);
555  CoverRow(row);
556  CoverCol(col);
557  break;
558  }
559  }
560  }
561  ClearCovers();
562  fn_state_ = std::bind(&HungarianOptimizer::CoverStarredZeroes, this);
563 }
564 
565 /* Step 3:
566  * Cover each column containing a starred zero. If all columns are covered,
567  * the starred zeros describe a complete set of unique assignments. In this
568  * case, terminate the algorithm. Otherwise, go to Step 4. */
569 template <typename T>
571  size_t num_covered = 0;
572 
573  for (size_t col = 0; col < matrix_size_; ++col) {
574  if (ColContainsStar(col)) {
575  CoverCol(col);
576  num_covered++;
577  }
578  }
579 
580  if (num_covered >= matrix_size_) {
581  fn_state_ = nullptr;
582  return;
583  }
584  fn_state_ = std::bind(&HungarianOptimizer::PrimeZeroes, this);
585 }
586 
587 /* Step 4:
588  * Find a noncovered zero and prime it. If there is no starred zero in the
589  * row containing this primed zero, go to Step 5. Otherwise, cover this row
590  * and uncover the column containing the starred zero. Continue in this manner
591  * until there are no uncovered zeros left, then go to Step 6. */
592 template <typename T>
594  // this loop is guaranteed to terminate in at most matrix_size_ iterations,
595  // as FindZero() returns a location only if there is at least one uncovered
596  // zero in the matrix. Each iteration, either one row is covered or the
597  // loop terminates. Since there are matrix_size_ rows, after that many
598  // iterations there are no uncovered cells and hence no uncovered zeroes,
599  // so the loop terminates.
600  for (;;) {
601  size_t zero_row = 0;
602  size_t zero_col = 0;
603  if (!FindZero(&zero_row, &zero_col)) {
604  // No uncovered zeroes.
605  fn_state_ = std::bind(&HungarianOptimizer::AugmentPath, this);
606  return;
607  }
608 
609  Prime(zero_row, zero_col);
610  int star_col = FindStarInRow(zero_row);
611 
612  if (star_col != kHungarianOptimizerColNotFound) {
613  CoverRow(zero_row);
614  UncoverCol(star_col);
615  } else {
616  std::pair<size_t, size_t> first_assignment =
617  std::make_pair(zero_row, zero_col);
618  assignments_[0] = first_assignment;
619  fn_state_ = std::bind(&HungarianOptimizer::MakeAugmentingPath, this);
620  return;
621  }
622  }
623 }
624 
625 /* Step 5:
626  * Construct a series of alternating primed and starred zeros as follows.
627  * Let Z0 represent the uncovered primed zero found in Step 4. Let Z1 denote
628  * the starred zero in the column of Z0 (if any). Let Z2 denote the primed
629  * zero in the row of Z1 (there will always be one). Continue until the
630  * series terminates at a primed zero that has no starred zero in its column.
631  * unstar each starred zero of the series, star each primed zero of the
632  * series, erase all primes and uncover every line in the matrix. Return to
633  * Step 3. */
634 template <typename T>
636  bool done = false;
637  size_t count = 0;
638 
639  /* note: this loop is guaranteed to terminate within matrix_size_ iterations
640  * because:
641  * 1) on entry to this step, there is at least 1 column with no starred zero
642  * (otherwise we would have terminated the algorithm already.)
643  * 2) each row containing a star also contains exactly one primed zero.
644  * 4) each column contains at most one starred zero.
645  *
646  * Since the path_ we construct visits primed and starred zeroes alternately,
647  * and terminates if we reach a primed zero in a column with no star, our
648  * path_ must either contain matrix_size_ or fewer stars (in which case the
649  * loop iterates fewer than matrix_size_ times), or it contains more. In
650  * that case, because (1) implies that there are fewer than matrix_size_
651  * stars, we must have visited at least one star more than once. Consider
652  * the first such star that we visit more than once; it must have been reached
653  * immediately after visiting a prime in the same row. By (2), this prime
654  * is unique and so must have also been visited more than once.
655  * Therefore, that prime must be in the same column as a star that has been
656  * visited more than once, contradicting the assumption that we chose the
657  * first multiply visited star, or it must be in the same column as more
658  * than one star, contradicting (3). Therefore, we never visit any star
659  * more than once and the loop terminates within matrix_size_ iterations. */
660 
661  while (!done) {
662  /* first construct the alternating path... */
663  int row = FindStarInCol(assignments_[count].second);
664 
665  if (row != kHungarianOptimizerRowNotFound) {
666  count++;
667  assignments_[count].first = row;
668  assignments_[count].second = assignments_[count - 1].second;
669  } else {
670  done = true;
671  }
672 
673  if (!done) {
674  int col = FindPrimeInRow(assignments_[count].first);
675  count++;
676  assignments_[count].first = assignments_[count - 1].first;
677  assignments_[count].second = col;
678  }
679  }
680 
681  /* then, modify it. */
682  for (size_t i = 0; i <= count; ++i) {
683  size_t row = assignments_[i].first;
684  size_t col = assignments_[i].second;
685 
686  if (IsStarred(row, col)) {
687  Unstar(row, col);
688  } else {
689  Star(row, col);
690  }
691  }
692 
693  ClearCovers();
694  ClearPrimes();
695  fn_state_ = std::bind(&HungarianOptimizer::CoverStarredZeroes, this);
696 }
697 
698 /* Step 6:
699  * Add the smallest uncovered value in the matrix to every element of each
700  * covered row, and subtract it from every element of each uncovered column.
701  * Return to Step 4 without altering any stars, primes, or covered lines. */
702 template <typename T>
704  T minval = FindSmallestUncovered();
705 
706  for (size_t row = 0; row < matrix_size_; ++row) {
707  if (RowCovered(row)) {
708  for (size_t c = 0; c < matrix_size_; ++c) {
709  costs_(row, c) += minval;
710  }
711  }
712  }
713  for (size_t col = 0; col < matrix_size_; ++col) {
714  if (!ColCovered(col)) {
715  for (size_t r = 0; r < matrix_size_; ++r) {
716  costs_(r, col) -= minval;
717  }
718  }
719  }
720  fn_state_ = std::bind(&HungarianOptimizer::PrimeZeroes, this);
721 }
722 
723 } // namespace common
724 } // namespace perception
725 } // namespace apollo
Definition: hungarian_optimizer.h:33
Definition: secure_matrix.h:29
~HungarianOptimizer()
Definition: hungarian_optimizer.h:41
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void OptimizationClear()
Definition: hungarian_optimizer.h:321
void OptimizationInit()
Definition: hungarian_optimizer.h:274
T * costs(const size_t row, const size_t col)
Definition: hungarian_optimizer.h:45
SecureMat< T > * costs()
Definition: hungarian_optimizer.h:43
HungarianOptimizer()
Definition: hungarian_optimizer.h:230
void Maximize(std::vector< std::pair< size_t, size_t >> *assignments)
Definition: hungarian_optimizer.h:248
void PrintMatrix()
Definition: hungarian_optimizer.h:465
void Minimize(std::vector< std::pair< size_t, size_t >> *assignments)
Definition: hungarian_optimizer.h:265