Autoware.Auto
autoware::common::helper_functions Namespace Reference

Namespaces

 comparisons
 
 message_field_adapters
 

Classes

class  ByteReader
 A utility class to read byte vectors in big-endian order. More...
 
class  crtp
 
class  LookupTable1D
 

Functions

template<typename T >
lookup_1d (const std::vector< T > &domain, const std::vector< T > &range, const T value)
 

Function Documentation

◆ lookup_1d()

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

Do a 1D table lookup: Does some semi-expensive O(N) error checking first. If query value fall out of the domain, then the value at the corresponding edge of the domain is returned.

Parameters
[in]domainThe domain, or set of x values
[in]rangeThe range, or set of y values
[in]valueThe point in the domain to query, x
Returns
A linearly interpolated value y, corresponding to the query, x
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
std::domain_errorIf value is not finite (NAN or INF)
Template Parameters
TThe type of the function, must be interpolatable