Public Member Functions | Protected Member Functions | Protected Attributes
srs_env_model::COcFilterGround Class Reference

#include <octomap_filter_ground.h>

Inheritance diagram for srs_env_model::COcFilterGround:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 COcFilterGround (const std::string &octree_frame_id, ERunMode mode=FILTER_ALLWAYS)
 Constructor.
tPointCloud * getGroundPc ()
 Get ground cloud.
tPointCloud * getNongroundPc ()
 Get non ground cloud.
virtual void init (ros::NodeHandle &node_handle)
 Initialize. Must be called before first filtering.
void setCloud (const tPointCloud *cloud)
 Configure filter before each frame. Set input cloud.
virtual void writeLastRunInfo ()
 Write some info about last filter run.

Protected Member Functions

virtual void filterInternal (tButServerOcTree &tree)
 Filtering function implementation.

Protected Attributes

double m_groundFilterAngle
double m_groundFilterDistance
double m_groundFilterPlaneDistance
tPointCloud * m_groundPc
 Ground cloud.
const tPointCloud * m_inputPc
 Input point cloud.
tPointCloud * m_nongroundPc
 Nonground cloud.
long m_numSpecRemoved
 Number of specles removed.

Detailed Description

Filter single specles from the octree

Definition at line 39 of file octomap_filter_ground.h.


Constructor & Destructor Documentation

srs_env_model::COcFilterGround::COcFilterGround ( const std::string &  octree_frame_id,
ERunMode  mode = FILTER_ALLWAYS 
)

Constructor.

Constructor

Definition at line 38 of file octomap_filter_ground.cpp.


Member Function Documentation

void srs_env_model::COcFilterGround::filterInternal ( tButServerOcTree &  tree) [protected, virtual]

Filtering function implementation.

Filtering function implementation

Reimplemented from srs_env_model::COcTreeFilterBase.

Definition at line 78 of file octomap_filter_ground.cpp.

Get ground cloud.

Definition at line 59 of file octomap_filter_ground.h.

Get non ground cloud.

Definition at line 62 of file octomap_filter_ground.h.

void srs_env_model::COcFilterGround::init ( ros::NodeHandle node_handle) [virtual]

Initialize. Must be called before first filtering.

Initialize. Must be called before first filtering

Definition at line 62 of file octomap_filter_ground.cpp.

void srs_env_model::COcFilterGround::setCloud ( const tPointCloud *  cloud)

Configure filter before each frame. Set input cloud.

Definition at line 53 of file octomap_filter_ground.cpp.

virtual void srs_env_model::COcFilterGround::writeLastRunInfo ( ) [inline, virtual]

Write some info about last filter run.

Reimplemented from srs_env_model::COcTreeFilterBase.

Definition at line 46 of file octomap_filter_ground.h.


Member Data Documentation

Definition at line 82 of file octomap_filter_ground.h.

Definition at line 81 of file octomap_filter_ground.h.

Definition at line 83 of file octomap_filter_ground.h.

Ground cloud.

Definition at line 76 of file octomap_filter_ground.h.

const tPointCloud* srs_env_model::COcFilterGround::m_inputPc [protected]

Input point cloud.

Definition at line 73 of file octomap_filter_ground.h.

Nonground cloud.

Definition at line 79 of file octomap_filter_ground.h.

Number of specles removed.

Definition at line 70 of file octomap_filter_ground.h.


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


srs_env_model
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Tomas Lokaj, Jan Gorig, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:50:50