|
Autoware.Auto
|
|
implementation of the hungarian/kuhn-munkres/jacobi algorithm for minimum weight assignment problem in O(N^3 ) time More...
#include <hungarian_assigner.hpp>
Public Member Functions | |
| hungarian_assigner_c () | |
| constructor More... | |
| hungarian_assigner_c (const index_t num_rows, const index_t num_cols) | |
| constructor, equivalent of construct(); set_size(num_rows, num_cols) More... | |
| void | set_size (const index_t num_rows, const index_t num_cols) |
| set the size of the matrix. Must be less than capacity. This should be done before set_weight() calls More... | |
| void | set_weight (const float32_t weight, const index_t idx, const index_t jdx) |
| set weight, update book-keeping for min in row This function is meant to be called asynchronously over jdx, so a thread should have fixed ownership over a given idx. Note that you can call this function again for a same index pair, but you will break assumptions if you set it to a higher weight. More... | |
| void | reset () |
| reset book-keeping and weight matrix, must be called after assign(), and before set_weight() More... | |
| void | reset (const index_t num_rows, const index_t num_cols) |
| reset and set_size, equivalent to reset(); set_size(num_rows, num_cols); More... | |
| bool8_t | assign () |
| compute minimum cost assignment More... | |
| index_t | get_assignment (const index_t idx) const |
| dictate what the assignment for a given row/task is, should be called after assign(). If assign() returned true, then every job/row is guaranteed to have a worker/column. If assign() returned false, then a row may not have a worker/column More... | |
| index_t | get_unassigned (const index_t idx) const |
| says what jobs have been unassigned More... | |
Static Public Attributes | |
| static constexpr index_t | UNASSIGNED = std::numeric_limits<index_t>::max() |
| This index denotes a worker for which no job assignment was possible. More... | |
implementation of the hungarian/kuhn-munkres/jacobi algorithm for minimum weight assignment problem in O(N^3 ) time
| Capacity | maximum number of things that can be matched, sets matrix size |
| autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::hungarian_assigner_c |
constructor
| autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::hungarian_assigner_c | ( | const index_t | num_rows, |
| const index_t | num_cols | ||
| ) |
constructor, equivalent of construct(); set_size(num_rows, num_cols)
| [in] | num_rows | number of rows/jobs |
| [in] | num_cols | number of columns/workers |
| bool8_t autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::assign |
compute minimum cost assignment
| std::exception | if some unspecified error happens internally, should never happen |
| index_t autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::get_assignment | ( | const index_t | idx | ) | const |
dictate what the assignment for a given row/task is, should be called after assign(). If assign() returned true, then every job/row is guaranteed to have a worker/column. If assign() returned false, then a row may not have a worker/column
| [in] | idx | the index for the task, starting at 0 |
| std::range_error | if idx is out of bounds |
| index_t autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::get_unassigned | ( | const index_t | idx | ) | const |
says what jobs have been unassigned
| [in] | idx | the i'th unassigned job, starts from 0 to num_jobs - num_workers |
| std::range_error | if idx is out of bounds (i.e. there are no unassigned rows) |
| void autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::reset |
reset book-keeping and weight matrix, must be called after assign(), and before set_weight()
| void autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::reset | ( | const index_t | num_rows, |
| const index_t | num_cols | ||
| ) |
reset and set_size, equivalent to reset(); set_size(num_rows, num_cols);
| [in] | num_rows | number of rows/jobs |
| [in] | num_cols | number of columns/workers |
| void autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::set_size | ( | const index_t | num_rows, |
| const index_t | num_cols | ||
| ) |
set the size of the matrix. Must be less than capacity. This should be done before set_weight() calls
| [in] | num_rows | number of rows/jobs |
| [in] | num_cols | number of columns/workers |
| std::length_error | if num_rows or num_cols is bigger than capacity |
| std::domain_error | if matrix shape is skinny |
| void autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::set_weight | ( | const float32_t | weight, |
| const index_t | idx, | ||
| const index_t | jdx | ||
| ) |
set weight, update book-keeping for min in row This function is meant to be called asynchronously over jdx, so a thread should have fixed ownership over a given idx. Note that you can call this function again for a same index pair, but you will break assumptions if you set it to a higher weight.
| [in] | weight | the weight for assignment of job idx to worker jdx |
| [in] | idx | the index of the job |
| [in] | jdx | the index of the worker |
| std::out_of_range | if idx or jdx are outside of range specified by set_size() |
|
staticconstexpr |
This index denotes a worker for which no job assignment was possible.