Public Member Functions | Public Attributes | List of all members
laser_filters::ScanShadowDetector Class Reference

#include <scan_shadow_detector.h>

Public Member Functions

void configure (const float min_angle, const float max_angle)
 
bool isShadow (const float r1, const float r2, const float included_angle)
 Check if the point is a shadow of another point within one laser scan. More...
 
bool isShadow (float r1, float r2, float included_angle_sin, float included_angle_cos)
 Check if the point is a shadow of another point within one laser scan. Use this method instead of the version without the extra parameters to avoid computing sin and cos of the angle on every execution. More...
 

Public Attributes

float max_angle_tan_
 
float min_angle_tan_
 

Detailed Description

Definition at line 78 of file scan_shadow_detector.h.

Member Function Documentation

◆ configure()

void laser_filters::ScanShadowDetector::configure ( const float  min_angle,
const float  max_angle 
)

Definition at line 77 of file scan_shadow_detector.cpp.

◆ isShadow() [1/2]

bool laser_filters::ScanShadowDetector::isShadow ( const float  r1,
const float  r2,
const float  included_angle 
)

Check if the point is a shadow of another point within one laser scan.

Parameters
r1the distance to the first point
r2the distance to the second point
included_anglethe angle between laser scans for these two points

Definition at line 89 of file scan_shadow_detector.cpp.

◆ isShadow() [2/2]

bool laser_filters::ScanShadowDetector::isShadow ( float  r1,
float  r2,
float  included_angle_sin,
float  included_angle_cos 
)

Check if the point is a shadow of another point within one laser scan. Use this method instead of the version without the extra parameters to avoid computing sin and cos of the angle on every execution.

Parameters
r1the distance to the first point
r2the distance to the second point
included_angle_sinthe sine of an angle between laser scans for these two points
included_angle_costhe cosine of an angle between laser scans for these two points

Definition at line 96 of file scan_shadow_detector.cpp.

Member Data Documentation

◆ max_angle_tan_

float laser_filters::ScanShadowDetector::max_angle_tan_

Definition at line 113 of file scan_shadow_detector.h.

◆ min_angle_tan_

float laser_filters::ScanShadowDetector::min_angle_tan_

Definition at line 113 of file scan_shadow_detector.h.


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


laser_filters
Author(s): Tully Foote
autogenerated on Mon Apr 3 2023 02:51:57