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

Simple stateful implementation of ray ground filter: https://github.com/CPFL/Autoware/blob/develop/ros/src/sensing/filters/packages/ points_preprocessor/nodes/ray_ground_ray_ground_filter/ray_ground_filter.cpp#L187. More...

#include <ray_ground_point_classifier.hpp>

Public Types

enum  PointLabel : int8_t {
  PointLabel::GROUND = 0, PointLabel::NONGROUND = 1, PointLabel::PROVISIONAL_GROUND = -1, PointLabel::RETRO_NONGROUND = 2,
  PointLabel::NONLOCAL_NONGROUND = 3
}
 Return codes from is_ground() More...
 

Public Member Functions

 RayGroundPointClassifier (const Config &config)
 Constructor. More...
 
 RayGroundPointClassifier (const RayGroundPointClassifier &original)
 Copy constructor. More...
 
void reset ()
 Reinitializes state of filter, should be run before scanning through a ray. More...
 
PointLabel is_ground (const PointXYZIFR &pt)
 Decides if point is ground or not based on locality to last point, max local and global slopes, dependent on and updates state. More...
 

Static Public Member Functions

static bool8_t label_is_ground (const PointLabel label)
 Whether a points label is abstractly ground or nonground. More...
 

Detailed Description

Simple stateful implementation of ray ground filter: https://github.com/CPFL/Autoware/blob/develop/ros/src/sensing/filters/packages/ points_preprocessor/nodes/ray_ground_ray_ground_filter/ray_ground_filter.cpp#L187.

Member Enumeration Documentation

◆ PointLabel

Return codes from is_ground()

Enumerator
GROUND 

Point is ground.

NONGROUND 

Point is nonground.

PROVISIONAL_GROUND 

Last point was nonground. This one is maybe ground. Label is solidified if terminal or next label is ground, otherwise nonground.

RETRO_NONGROUND 

point is so vertical wrt last that last point is also nonground

NONLOCAL_NONGROUND 

last was provisional ground, but this point is distant

Constructor & Destructor Documentation

◆ RayGroundPointClassifier() [1/2]

autoware::perception::filters::ray_ground_classifier::RayGroundPointClassifier::RayGroundPointClassifier ( const Config config)
explicit

Constructor.

Parameters
[in]configThe configuration struct for the filter
Exceptions
std::runtime_errorif the configuration is invalid

◆ RayGroundPointClassifier() [2/2]

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

Copy constructor.

Member Function Documentation

◆ is_ground()

RayGroundPointClassifier::PointLabel autoware::perception::filters::ray_ground_classifier::RayGroundPointClassifier::is_ground ( const PointXYZIFR pt)

Decides if point is ground or not based on locality to last point, max local and global slopes, dependent on and updates state.

Parameters
[in]ptThe point to be classified as ground or not ground
Returns
PointLabel::GROUND if the point is classified as ground PointLabel::NONGROUND if the point is classified as not ground PointLabel::RETRO_NONGROUND if the point is classified as not ground and the point is so vertical that the last point should also be ground
Exceptions
std::runtime_errorif points are not received in order of increasing radius

◆ label_is_ground()

bool8_t autoware::perception::filters::ray_ground_classifier::RayGroundPointClassifier::label_is_ground ( const PointLabel  label)
static

Whether a points label is abstractly ground or nonground.

Parameters
[in]labelthe label to check whether or not its ground
Returns
True if ground or provisionally ground, false if nonground or retro nonground

◆ reset()

void autoware::perception::filters::ray_ground_classifier::RayGroundPointClassifier::reset ( )

Reinitializes state of filter, should be run before scanning through a ray.


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