Autoware.Auto
autoware::perception::filters::ray_ground_classifier::RayGroundClassifier Class Reference

Given a ray, partitions into ground and nonground points. More...

#include <ray_ground_classifier.hpp>

Public Member Functions

 RayGroundClassifier (const Config &cfg)
 Default constructor. More...
 
 RayGroundClassifier (const RayGroundClassifier &original)
 Copy constructor. More...
 
void insert (const PointXYZIF *pt)
 Inserts a point into the internal datastructure, intended to be used with filter. Points inserted sequentially should have the semantics of being a part of the same ray. More...
 
void insert (const PointXYZIFR &pt)
 Inserts a point into the internal datastructure, intended to be used with filter. Points inserted sequentially should have the semantics of being a part of the same ray. More...
 
bool8_t can_fit_result (const PointPtrBlock &ground_block, const PointPtrBlock &nonground_block) const
 check if the provided output blocks can definitely fit the result of a partition More...
 
bool8_t can_fit_result (const Ray &ray, const PointPtrBlock &ground_block, const PointPtrBlock &nonground_block) const
 check if the provided output blocks can definitely fit the result of a partition More...
 
void partition (PointPtrBlock &ground_block, PointPtrBlock &nonground_block, const bool8_t presorted)
 Partitions points from a single ray that were inserted using insert as ground or nonground. More...
 
void structured_partition (const PointPtrBlock &raw_block, PointPtrBlock &ground_block, PointPtrBlock &nonground_block)
 Partitions points from raw block into ground points and nonground points. More...
 
void partition (const Ray &ray, PointPtrBlock &ground_block, PointPtrBlock &nonground_block)
 Logic for making labels consistent throughout a single ray. More...
 

Detailed Description

Given a ray, partitions into ground and nonground points.

Constructor & Destructor Documentation

◆ RayGroundClassifier() [1/2]

autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::RayGroundClassifier ( const Config cfg)
explicit

Default constructor.

Parameters
[in]cfgRay ground filter configuration parameters

◆ RayGroundClassifier() [2/2]

autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::RayGroundClassifier ( const RayGroundClassifier original)
explicit

Copy constructor.

Member Function Documentation

◆ can_fit_result() [1/2]

bool8_t autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::can_fit_result ( const PointPtrBlock &  ground_block,
const PointPtrBlock &  nonground_block 
) const

check if the provided output blocks can definitely fit the result of a partition

Parameters
[in]ground_blockThe block that should hold the resulting ground points
[in]nonground_blockThe block that should hold the resulting nonground points
Returns
false if provided output blocks could not fit ray

◆ can_fit_result() [2/2]

bool8_t autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::can_fit_result ( const Ray ray,
const PointPtrBlock &  ground_block,
const PointPtrBlock &  nonground_block 
) const

check if the provided output blocks can definitely fit the result of a partition

Parameters
[in]ground_blockThe block that should hold the resulting ground points
[in]nonground_blockThe block that should hold the resulting nonground points
[in]rayThe ray to be partitioned
Returns
false if provided output blocks could not fit ray

◆ insert() [1/2]

void autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::insert ( const PointXYZIF pt)

Inserts a point into the internal datastructure, intended to be used with filter. Points inserted sequentially should have the semantics of being a part of the same ray.

Parameters
[in]ptThe point to insert
Exceptions
std::runtime_errorIf the internal datastructure is full

◆ insert() [2/2]

void autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::insert ( const PointXYZIFR pt)

Inserts a point into the internal datastructure, intended to be used with filter. Points inserted sequentially should have the semantics of being a part of the same ray.

Parameters
[in]ptThe point to insert
Exceptions
std::runtime_errorIf the internal datastructure is full

◆ partition() [1/2]

void autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::partition ( const Ray ray,
PointPtrBlock &  ground_block,
PointPtrBlock &  nonground_block 
)

Logic for making labels consistent throughout a single ray.

Parameters
[in]rayDatastructure which holds a sorted ray
[in,out]ground_blockGets appended with ground points, size is respected and modified
[in,out]nonground_blockGets appended with nonground points, size is respected and modified
Exceptions
std::runtime_errorIf blocks cannot fit result

◆ partition() [2/2]

void autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::partition ( PointPtrBlock &  ground_block,
PointPtrBlock &  nonground_block,
const bool8_t  presorted 
)

Partitions points from a single ray that were inserted using insert as ground or nonground.

Parameters
[in,out]ground_blockGets appended with ground partition of the ray. The size parameter is honored and modified.
[in,out]nonground_blockGets appended with nonground partition of the ray. The size parameter is honored and modified.
[in]presortedIf true, does not do a sorting step. Should only be true if the ray points are inserted in order of increasing radial distance, and in order of increasing height in the case of a tie
Exceptions
std::runtime_errorIf blocks cannot fit result

◆ structured_partition()

void autoware::perception::filters::ray_ground_classifier::RayGroundClassifier::structured_partition ( const PointPtrBlock &  raw_block,
PointPtrBlock &  ground_block,
PointPtrBlock &  nonground_block 
)

Partitions points from raw block into ground points and nonground points.

Parameters
[in]raw_blockA full point block of one or more rays. Rays are assumed to be contiguous in the block, e.g. a ray label sequence of 1-1-2-2-1-1 is viewed as 3 rays
[out]ground_blockGets filled with ground partition of the ray. The size parameter is overwritten
[out]nonground_blockGets filled with nonground partition of the ray. The size parameter is overwritten

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