20 #ifndef HUNGARIAN_ASSIGNER__HUNGARIAN_ASSIGNER_HPP_
21 #define HUNGARIAN_ASSIGNER__HUNGARIAN_ASSIGNER_HPP_
25 #define EIGEN_NO_MALLOC
26 #define EIGEN_STACK_ALLOCATION_LIMIT 0
45 namespace hungarian_assigner
54 template<u
int16_t Capacity>
57 static_assert(Capacity > 0,
"Capacity must be positive");
69 using index2_t = std::pair<index_t, index_t>;
73 class HUNGARIAN_ASSIGNER_LOCAL no_uncovered_values_c :
public std::runtime_error
76 no_uncovered_values_c();
81 static constexpr
index_t UNASSIGNED = std::numeric_limits<index_t>::max();
82 static constexpr
float MAX_WEIGHT = 10000.F;
148 HUNGARIAN_ASSIGNER_LOCAL
void find_minimums();
150 HUNGARIAN_ASSIGNER_LOCAL
bool8_t reduce_rows_and_init_zeros_and_check_result();
153 HUNGARIAN_ASSIGNER_LOCAL
bool8_t increment_starred_zeroes_and_check_result(index2_t loc);
156 HUNGARIAN_ASSIGNER_LOCAL index2_t prime_uncovered_zero();
159 HUNGARIAN_ASSIGNER_LOCAL
bool8_t add_new_zero(index2_t & loc);
162 HUNGARIAN_ASSIGNER_LOCAL
bool8_t are_all_columns_covered()
const;
165 HUNGARIAN_ASSIGNER_LOCAL
bool8_t find_uncovered_zero(index2_t & loc)
const;
168 HUNGARIAN_ASSIGNER_LOCAL
bool8_t find_minimum_uncovered_value(
173 HUNGARIAN_ASSIGNER_LOCAL
void update_uncovered_rows_and_cols();
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;
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;
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;
199 #endif // HUNGARIAN_ASSIGNER__HUNGARIAN_ASSIGNER_HPP_