#include <octomap_filter_base.h>
Public Types | |
enum | ERunMode { FILTER_ALLWAYS, FILTER_TEST_FRAME, FILTER_TEST_TIME } |
Running mode. More... | |
Public Member Functions | |
COcTreeFilterBase (const std::string &octree_frame_id, ERunMode mode=FILTER_ALLWAYS) | |
Constructor - set running mode. | |
void | filter (tButServerOcTree &tree, bool bPruneAfterFinish=true) |
Filter tree. | |
void | setFrameSkip (unsigned skip) |
Set number of frames skipped between runs. | |
void | setRunMode (ERunMode mode) |
Set filter running mode. | |
bool | setTimerLap (double lap) |
Set timer lap. | |
void | setTreeFrameId (const std::string &tree_frame_id) |
Set tree frame id. | |
virtual void | writeLastRunInfo () |
Write some info about last filter run. | |
Protected Member Functions | |
virtual void | filterInternal (tButServerOcTree &tree) |
Filtering function implementation. | |
bool | useFrame () |
Test if this frame should be used. | |
Protected Attributes | |
long | m_framesCount |
Frames counter. | |
unsigned | m_framesSkipped |
How many frames should be skipped between runs. | |
double | m_lap |
Timer lap. | |
ERunMode | m_mode |
Used running mode. | |
boost::timer | m_timer |
Timer. | |
std::string | m_treeFrameId |
Tree frame id. |
Definition at line 38 of file octomap_filter_base.h.
Running mode.
Definition at line 42 of file octomap_filter_base.h.
srs_env_model::COcTreeFilterBase::COcTreeFilterBase | ( | const std::string & | octree_frame_id, |
ERunMode | mode = FILTER_ALLWAYS |
||
) |
Constructor - set running mode.
Definition at line 30 of file octomap_filter_base.cpp.
void srs_env_model::COcTreeFilterBase::filter | ( | tButServerOcTree & | tree, |
bool | bPruneAfterFinish = true |
||
) |
virtual void srs_env_model::COcTreeFilterBase::filterInternal | ( | tButServerOcTree & | tree | ) | [inline, protected, virtual] |
Filtering function implementation.
Reimplemented in srs_env_model::COcFilterGround, srs_env_model::COcFilterRaycast, and srs_env_model::COcFilterSingleSpecles.
Definition at line 76 of file octomap_filter_base.h.
void srs_env_model::COcTreeFilterBase::setFrameSkip | ( | unsigned | skip | ) |
Set number of frames skipped between runs.
Set number of frames skipped between runs
Definition at line 43 of file octomap_filter_base.cpp.
void srs_env_model::COcTreeFilterBase::setRunMode | ( | ERunMode | mode | ) | [inline] |
Set filter running mode.
Definition at line 63 of file octomap_filter_base.h.
bool srs_env_model::COcTreeFilterBase::setTimerLap | ( | double | lap | ) |
Set timer lap.
Set timer lap
Definition at line 52 of file octomap_filter_base.cpp.
void srs_env_model::COcTreeFilterBase::setTreeFrameId | ( | const std::string & | tree_frame_id | ) | [inline] |
Set tree frame id.
Definition at line 66 of file octomap_filter_base.h.
bool srs_env_model::COcTreeFilterBase::useFrame | ( | ) | [protected] |
Test if this frame should be used.
Test if this frame should be used
Definition at line 82 of file octomap_filter_base.cpp.
virtual void srs_env_model::COcTreeFilterBase::writeLastRunInfo | ( | ) | [inline, virtual] |
Write some info about last filter run.
Reimplemented in srs_env_model::COcFilterRaycast, srs_env_model::COcFilterGround, and srs_env_model::COcFilterSingleSpecles.
Definition at line 69 of file octomap_filter_base.h.
long srs_env_model::COcTreeFilterBase::m_framesCount [protected] |
Frames counter.
Definition at line 86 of file octomap_filter_base.h.
unsigned srs_env_model::COcTreeFilterBase::m_framesSkipped [protected] |
How many frames should be skipped between runs.
Definition at line 83 of file octomap_filter_base.h.
double srs_env_model::COcTreeFilterBase::m_lap [protected] |
Timer lap.
Definition at line 92 of file octomap_filter_base.h.
ERunMode srs_env_model::COcTreeFilterBase::m_mode [protected] |
Used running mode.
Definition at line 80 of file octomap_filter_base.h.
Definition at line 89 of file octomap_filter_base.h.
std::string srs_env_model::COcTreeFilterBase::m_treeFrameId [protected] |
Tree frame id.
Definition at line 95 of file octomap_filter_base.h.