Autoware.Auto
autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity > Class Template Reference

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...
 

Detailed Description

template<uint16_t Capacity>
class autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >

implementation of the hungarian/kuhn-munkres/jacobi algorithm for minimum weight assignment problem in O(N^3 ) time

Template Parameters
Capacitymaximum number of things that can be matched, sets matrix size

Constructor & Destructor Documentation

◆ hungarian_assigner_c() [1/2]

constructor

◆ hungarian_assigner_c() [2/2]

template<uint16_t Capacity>
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)

Parameters
[in]num_rowsnumber of rows/jobs
[in]num_colsnumber of columns/workers

Member Function Documentation

◆ assign()

template<uint16_t Capacity>
bool8_t autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::assign ( )

compute minimum cost assignment

Returns
whether or not it was successful. If assignment was unsuccessful (for example, the case when a row has no valid assignments), then get_assignment() may return UNASSIGNED
Exceptions
std::exceptionif some unspecified error happens internally, should never happen

◆ get_assignment()

template<uint16_t Capacity>
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

Parameters
[in]idxthe index for the task, starting at 0
Returns
the index for the assigned job, starting at 0 UNASSIGNED if assign() returned false and the idx job has no possible assignments
Exceptions
std::range_errorif idx is out of bounds

◆ get_unassigned()

template<uint16_t Capacity>
index_t autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::get_unassigned ( const index_t  idx) const

says what jobs have been unassigned

Parameters
[in]idxthe i'th unassigned job, starts from 0 to num_jobs - num_workers
Returns
the index of the i'th unassigned job
Exceptions
std::range_errorif idx is out of bounds (i.e. there are no unassigned rows)

◆ reset() [1/2]

template<uint16_t Capacity>
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()

◆ reset() [2/2]

template<uint16_t Capacity>
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);

Parameters
[in]num_rowsnumber of rows/jobs
[in]num_colsnumber of columns/workers

◆ set_size()

template<uint16_t Capacity>
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

Parameters
[in]num_rowsnumber of rows/jobs
[in]num_colsnumber of columns/workers
Exceptions
std::length_errorif num_rows or num_cols is bigger than capacity
std::domain_errorif matrix shape is skinny

◆ set_weight()

template<uint16_t Capacity>
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.

Parameters
[in]weightthe weight for assignment of job idx to worker jdx
[in]idxthe index of the job
[in]jdxthe index of the worker
Exceptions
std::out_of_rangeif idx or jdx are outside of range specified by set_size()

Member Data Documentation

◆ UNASSIGNED

template<uint16_t Capacity>
constexpr index_t autoware::fusion::hungarian_assigner::hungarian_assigner_c< Capacity >::UNASSIGNED = std::numeric_limits<index_t>::max()
static

This index denotes a worker for which no job assignment was possible.


The documentation for this class was generated from the following files: