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();
145 HUNGARIAN_ASSIGNER_LOCAL
bool8_t reduce_rows_and_init_zeros_and_check_result();
148 HUNGARIAN_ASSIGNER_LOCAL
bool8_t increment_starred_zeroes_and_check_result(index2_t loc);
151 HUNGARIAN_ASSIGNER_LOCAL index2_t prime_uncovered_zero();
154 HUNGARIAN_ASSIGNER_LOCAL
bool8_t add_new_zero(index2_t & loc);
157 HUNGARIAN_ASSIGNER_LOCAL
bool8_t are_all_columns_covered()
const;
160 HUNGARIAN_ASSIGNER_LOCAL
bool8_t find_uncovered_zero(index2_t & loc)
const;
163 HUNGARIAN_ASSIGNER_LOCAL
bool8_t find_minimum_uncovered_value(
168 HUNGARIAN_ASSIGNER_LOCAL
void update_uncovered_rows_and_cols();
170 Eigen::Matrix<float32_t, Capacity, Capacity> m_weight_matrix;
171 Eigen::Matrix<int8_t, Capacity, Capacity> m_mark_matrix;
172 Eigen::Matrix<index_t, Capacity, 1> m_row_min_idx;
175 Eigen::Matrix<float32_t, Capacity, 1> m_row_min_weights;
176 Eigen::Matrix<index_t, Capacity, 1> m_assignments;
177 Eigen::Matrix<bool8_t, Capacity, 1> m_is_col_covered;
178 Eigen::Matrix<bool8_t, Capacity, 1> m_is_row_covered;
181 Eigen::Matrix<index_t, Capacity, 1> m_uncovered_rows;
182 Eigen::Matrix<index_t, Capacity, 1> m_uncovered_cols;
183 Eigen::Matrix<index2_t, 2 * Capacity, 1> m_augment_path;
184 Eigen::Matrix<index2_t, Capacity, 1> m_primed_zero_locs;
191 #endif // HUNGARIAN_ASSIGNER__HUNGARIAN_ASSIGNER_HPP_