|
Autoware.Auto
|
|
#include <lookup_table.hpp>
Public Member Functions | |
| LookupTable1D (const std::vector< T > &domain, const std::vector< T > &range) | |
| LookupTable1D (std::vector< T > &&domain, std::vector< T > &&range) | |
| T | lookup (const T value) const |
| const std::vector< T > & | domain () const noexcept |
| Get the domain table. More... | |
| const std::vector< T > & | range () const noexcept |
| Get the range table. More... | |
A class wrapping a 1D lookup table. Intended for more frequent lookups. Error checking is pushed into the constructor and not done in the lookup function call
| T | The type of the function, must be interpolatable |
|
inline |
Constructor
| [in] | domain | The domain, or set of x values |
| [in] | range | The range, or set of y values |
| std::domain_error | If domain or range is empty |
| std::domain_error | If range is not the same size as domain |
| std::domain_error | If domain is not sorted |
|
inline |
Move constructor
| [in] | domain | The domain, or set of x values |
| [in] | range | The range, or set of y values |
| std::domain_error | If domain or range is empty |
| std::domain_error | If range is not the same size as domain |
| std::domain_error | If domain is not sorted |
|
inlinenoexcept |
Get the domain table.
|
inline |
Do a 1D table lookup If query value fall out of the domain, then the value at the corresponding edge of the domain is returned.
| [in] | value | The point in the domain to query, x |
| std::domain_error | If value is not finite |
|
inlinenoexcept |
Get the range table.