Autoware.Auto
autoware::common::helper_functions::LookupTable1D< T > Class Template Reference

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

Detailed Description

template<typename T>
class autoware::common::helper_functions::LookupTable1D< T >

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

Template Parameters
TThe type of the function, must be interpolatable

Constructor & Destructor Documentation

◆ LookupTable1D() [1/2]

template<typename T >
autoware::common::helper_functions::LookupTable1D< T >::LookupTable1D ( const std::vector< T > &  domain,
const std::vector< T > &  range 
)
inline

Constructor

Parameters
[in]domainThe domain, or set of x values
[in]rangeThe range, or set of y values
Exceptions
std::domain_errorIf domain or range is empty
std::domain_errorIf range is not the same size as domain
std::domain_errorIf domain is not sorted

◆ LookupTable1D() [2/2]

template<typename T >
autoware::common::helper_functions::LookupTable1D< T >::LookupTable1D ( std::vector< T > &&  domain,
std::vector< T > &&  range 
)
inline

Move constructor

Parameters
[in]domainThe domain, or set of x values
[in]rangeThe range, or set of y values
Exceptions
std::domain_errorIf domain or range is empty
std::domain_errorIf range is not the same size as domain
std::domain_errorIf domain is not sorted

Member Function Documentation

◆ domain()

template<typename T >
const std::vector<T>& autoware::common::helper_functions::LookupTable1D< T >::domain ( ) const
inlinenoexcept

Get the domain table.

◆ lookup()

template<typename T >
T autoware::common::helper_functions::LookupTable1D< T >::lookup ( const T  value) const
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.

Parameters
[in]valueThe point in the domain to query, x
Returns
A linearly interpolated value y, corresponding to the query, x
Exceptions
std::domain_errorIf value is not finite

◆ range()

template<typename T >
const std::vector<T>& autoware::common::helper_functions::LookupTable1D< T >::range ( ) const
inlinenoexcept

Get the range table.


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