Filter class to check if a point's azimuth lies within a range defined by a start and end angles. The range is defined from start to the end angles in counter-clock-wise direction.
More...
#include <point_cloud_utils.hpp>
|
| AngleFilter (float32_t start_angle, float32_t end_angle) |
| Constructor. More...
|
|
template<typename T > |
bool8_t | operator() (const T &pt) const |
| Check if a point's azimuth lies in the range [start, end] in counter-clock-wise-direction. The point is treated as a 2D vector whose projection on the range normal is compared to a threshold. More...
|
|
|
static constexpr float32_t | PI = 3.14159265359F |
|
static constexpr auto | FEPS = std::numeric_limits<float32_t>::epsilon() * 1e2F |
|
Filter class to check if a point's azimuth lies within a range defined by a start and end angles. The range is defined from start to the end angles in counter-clock-wise direction.
◆ VectorT
◆ AngleFilter()
autoware::common::lidar_utils::AngleFilter::AngleFilter |
( |
float32_t |
start_angle, |
|
|
float32_t |
end_angle |
|
) |
| |
Constructor.
- Parameters
-
start_angle | Minimum angle in radians |
end_angle | Maximum angle in radians |
◆ operator()()
template<typename T >
bool8_t autoware::common::lidar_utils::AngleFilter::operator() |
( |
const T & |
pt | ) |
const |
|
inline |
Check if a point's azimuth lies in the range [start, end] in counter-clock-wise-direction. The point is treated as a 2D vector whose projection on the range normal is compared to a threshold.
- Template Parameters
-
- Parameters
-
- Returns
- return true if the point is contained within the range.
◆ FEPS
constexpr auto autoware::common::lidar_utils::AngleFilter::FEPS = std::numeric_limits<float32_t>::epsilon() * 1e2F |
|
staticconstexpr |
◆ PI
constexpr float32_t autoware::common::lidar_utils::AngleFilter::PI = 3.14159265359F |
|
staticconstexpr |
The documentation for this class was generated from the following files: