Autoware.Auto
hungarian_assigner.hpp
Go to the documentation of this file.
1 // Copyright 2018 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
20 #ifndef HUNGARIAN_ASSIGNER__HUNGARIAN_ASSIGNER_HPP_
21 #define HUNGARIAN_ASSIGNER__HUNGARIAN_ASSIGNER_HPP_
22 
23 
25 #define EIGEN_NO_MALLOC
26 #define EIGEN_STACK_ALLOCATION_LIMIT 0
28 
29 #include <Eigen/Core>
31 #include <utility>
32 #include <limits>
33 #include <array>
34 #include "common/types.hpp"
35 
38 
39 namespace autoware
40 {
41 namespace fusion
42 {
45 namespace hungarian_assigner
46 {
47 
50 
54 template<uint16_t Capacity>
55 class HUNGARIAN_ASSIGNER_PUBLIC hungarian_assigner_c
56 {
57  static_assert(Capacity > 0, "Capacity must be positive");
59  enum mark_e : int8_t
60  {
61  NO_LINK = 0,
62  UNMARKED = 1,
63  ZERO = 2,
64  PRIMED = 3,
65  STARRED = 4
66  };
67 
69  using index2_t = std::pair<index_t, index_t>;
70 
73  class HUNGARIAN_ASSIGNER_LOCAL no_uncovered_values_c : public std::runtime_error
74  {
75 public:
76  no_uncovered_values_c();
77  }; // class no_uncovered_values_c
78 
79 public:
81  static constexpr index_t UNASSIGNED = std::numeric_limits<index_t>::max();
82  static constexpr float MAX_WEIGHT = 10000.F;
83 
86 
90  hungarian_assigner_c(const index_t num_rows, const index_t num_cols);
91 
98  void set_size(const index_t num_rows, const index_t num_cols);
99 
109  void set_weight(const float32_t weight, const index_t idx, const index_t jdx);
110 
113  void reset();
114 
118  void reset(const index_t num_rows, const index_t num_cols);
119 
125  bool8_t assign();
126 
127  // every row/job is guaranteed to have a worker
135  index_t get_assignment(const index_t idx) const;
136 
137  // get unassigned workers/columns. User should know how many unassigned there will be apriori
142  index_t get_unassigned(const index_t idx) const;
143 
144 private:
145  // TODO(gowtham.ranganathan): Workaround. Should calculate minimum while the weight is being
146  // set. Fix after #979.
148  HUNGARIAN_ASSIGNER_LOCAL void find_minimums();
150  HUNGARIAN_ASSIGNER_LOCAL bool8_t reduce_rows_and_init_zeros_and_check_result();
151 
153  HUNGARIAN_ASSIGNER_LOCAL bool8_t increment_starred_zeroes_and_check_result(index2_t loc);
154 
156  HUNGARIAN_ASSIGNER_LOCAL index2_t prime_uncovered_zero();
157 
159  HUNGARIAN_ASSIGNER_LOCAL bool8_t add_new_zero(index2_t & loc);
160 
162  HUNGARIAN_ASSIGNER_LOCAL bool8_t are_all_columns_covered() const;
163 
165  HUNGARIAN_ASSIGNER_LOCAL bool8_t find_uncovered_zero(index2_t & loc) const;
166 
168  HUNGARIAN_ASSIGNER_LOCAL bool8_t find_minimum_uncovered_value(
169  index2_t & loc,
170  float32_t & min_val) const;
171 
173  HUNGARIAN_ASSIGNER_LOCAL void update_uncovered_rows_and_cols();
174 
175  // TODO(gowtham.ranganathan): Workaround. There should be no need for m_is_max_matrix after #979
176  // Matrix to track if a weight is unset (set to max means unset)
177  Eigen::Matrix<bool8_t, Capacity, Capacity> m_is_max_matrix;
178  Eigen::Matrix<float32_t, Capacity, Capacity> m_weight_matrix;
179  Eigen::Matrix<int8_t, Capacity, Capacity> m_mark_matrix;
180  Eigen::Matrix<index_t, Capacity, 1> m_row_min_idx;
181  index_t m_num_rows;
182  index_t m_num_cols;
183  Eigen::Matrix<float32_t, Capacity, 1> m_row_min_weights;
184  Eigen::Matrix<index_t, Capacity, 1> m_assignments;
185  Eigen::Matrix<bool8_t, Capacity, 1> m_is_col_covered;
186  Eigen::Matrix<bool8_t, Capacity, 1> m_is_row_covered;
187  index_t m_num_uncovered_rows;
188  index_t m_num_uncovered_cols;
189  Eigen::Matrix<index_t, Capacity, 1> m_uncovered_rows;
190  Eigen::Matrix<index_t, Capacity, 1> m_uncovered_cols;
191  Eigen::Matrix<index2_t, 2 * Capacity, 1> m_augment_path;
192  Eigen::Matrix<index2_t, Capacity, 1> m_primed_zero_locs;
193  index_t m_num_primed_zeros;
194 }; // class hungarian_assigner_c
195 
196 } // namespace hungarian_assigner
197 } // namespace fusion
198 } // namespace autoware
199 #endif // HUNGARIAN_ASSIGNER__HUNGARIAN_ASSIGNER_HPP_
types.hpp
This file includes common type definition.
autoware::fusion::hungarian_assigner::index_t
Eigen::Index index_t
indexing matches what matrices use
Definition: hungarian_assigner.hpp:49
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
visibility_control.hpp
autoware::fusion::hungarian_assigner::hungarian_assigner_c
implementation of the hungarian/kuhn-munkres/jacobi algorithm for minimum weight assignment problem i...
Definition: hungarian_assigner.hpp:55
autoware::common::geometry::spatial_hash::Index
std::size_t Index
Index type for identifying bins of the hash/lattice.
Definition: spatial_hash_config.hpp:49