Autoware.Auto
autoware::common::lidar_utils::DistanceFilter Class Reference

Filter class to check if a point lies within a range defined by a min and max radius. More...

#include <point_cloud_utils.hpp>

Public Member Functions

 DistanceFilter (float32_t min_radius, float32_t max_radius)
 Cosntructor. More...
 
template<typename T >
bool8_t operator() (const T &pt) const
 Check if the point is within the allowed range of the filter. Check is done in square form to avoid sqrt More...
 

Static Public Attributes

static constexpr auto FEPS = std::numeric_limits<float32_t>::epsilon()
 

Detailed Description

Filter class to check if a point lies within a range defined by a min and max radius.

Constructor & Destructor Documentation

◆ DistanceFilter()

autoware::common::lidar_utils::DistanceFilter::DistanceFilter ( float32_t  min_radius,
float32_t  max_radius 
)

Cosntructor.

Parameters
min_radiusThe radius the point's radius should be greater than
max_radiusThe radius the point's radius should be lesser than

Member Function Documentation

◆ operator()()

template<typename T >
bool8_t autoware::common::lidar_utils::DistanceFilter::operator() ( const T &  pt) const
inline

Check if the point is within the allowed range of the filter. Check is done in square form to avoid sqrt

Template Parameters
TPoint type
Parameters
ptPoint to be filtered
Returns
True if point is within the filter's range.

Member Data Documentation

◆ FEPS

constexpr float32_t autoware::common::lidar_utils::DistanceFilter::FEPS = std::numeric_limits<float32_t>::epsilon()
staticconstexpr

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