Public Member Functions | Private Attributes | List of all members
mitre_fast_layered_map::BayesUpdate Class Reference

#include <filters.hpp>

Inheritance diagram for mitre_fast_layered_map::BayesUpdate:
Inheritance graph
[legend]

Public Member Functions

 BayesUpdate ()
 
virtual bool configure ()
 
double dynamicSenseOccGivenEmp (int numHits)
 
double dynamicSenseOccGivenOcc (int numHits)
 
virtual bool update (const grid_map::GridMap &_mapIn, grid_map::GridMap &_mapOut)
 
virtual ~BayesUpdate ()
 
- Public Member Functions inherited from filters::FilterBase< grid_map::GridMap >
bool configure (const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
 
bool configure (XmlRpc::XmlRpcValue &config)
 
 FilterBase ()
 
const std::string & getName ()
 
std::string getType ()
 
virtual ~FilterBase ()
 

Private Attributes

int historyCount_
 Num history layers use. More...
 
std::string historyLayerPrefix_
 Prefix for historys layers. Should follow prefix + (int) i standard. More...
 
std::string probabilityLayerStr_
 Layer that holds accumulated probability until now. More...
 
double probSenseEmpGivenEmp_ {0.8}
 
double probSenseEmpGivenOcc_ {0.4}
 
double probSenseOccGivenEmpOffset_ {0.3}
 
double probSenseOccGivenEmpRate_ {-0.1}
 
double probSenseOccGivenOccOffset_ {0.3}
 
double probSenseOccGivenOccRate_ {0.1}
 
double startingProb_ {0.5}
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< grid_map::GridMap >
bool getParam (const std::string &name, std::string &value)
 
bool getParam (const std::string &name, XmlRpc::XmlRpcValue &value)
 
bool getParam (const std::string &name, double &value)
 
bool getParam (const std::string &name, std::vector< double > &value)
 
bool getParam (const std::string &name, unsigned int &value)
 
bool getParam (const std::string &name, int &value)
 
bool getParam (const std::string &name, std::vector< std::string > &value)
 
bool getParam (const std::string &name, bool &value)
 
bool loadConfiguration (XmlRpc::XmlRpcValue &config)
 
- Protected Attributes inherited from filters::FilterBase< grid_map::GridMap >
bool configured_
 
std::string filter_name_
 
std::string filter_type_
 
string_map_t params_
 

Detailed Description

Definition at line 107 of file filters.hpp.

Constructor & Destructor Documentation

mitre_fast_layered_map::BayesUpdate::BayesUpdate ( )

Definition at line 16 of file bayes_update.cpp.

mitre_fast_layered_map::BayesUpdate::~BayesUpdate ( )
virtual

Definition at line 20 of file bayes_update.cpp.

Member Function Documentation

bool mitre_fast_layered_map::BayesUpdate::configure ( )
virtual

Implements filters::FilterBase< grid_map::GridMap >.

Definition at line 24 of file bayes_update.cpp.

double mitre_fast_layered_map::BayesUpdate::dynamicSenseOccGivenEmp ( int  numHits)

Opposite of previous function. We lose confidence that a cell is empty occupied as the number of readings increases y = -0.1 * readings + 0.3

Definition at line 204 of file bayes_update.cpp.

double mitre_fast_layered_map::BayesUpdate::dynamicSenseOccGivenOcc ( int  numHits)

: Make this customizable to allow for other sensor architectures This and the function below can be thought of a bit like a modified RELU function. Using this function we can dynamically modify our confidence in our sensor readings based on the number of points that were sensed in a given cell. y = 0.05 * readings + 0.5 - line formula 0.99 is max confidence of obstacle we will allow

Definition at line 194 of file bayes_update.cpp.

bool mitre_fast_layered_map::BayesUpdate::update ( const grid_map::GridMap _mapIn,
grid_map::GridMap _mapOut 
)
virtual

Updates the probability that a cell is occupied Algorithm found in https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=30720 : This function can probably be vectorized for performance gains

Implements filters::FilterBase< grid_map::GridMap >.

Definition at line 98 of file bayes_update.cpp.

Member Data Documentation

int mitre_fast_layered_map::BayesUpdate::historyCount_
private

Num history layers use.

Definition at line 124 of file filters.hpp.

std::string mitre_fast_layered_map::BayesUpdate::historyLayerPrefix_
private

Prefix for historys layers. Should follow prefix + (int) i standard.

Definition at line 123 of file filters.hpp.

std::string mitre_fast_layered_map::BayesUpdate::probabilityLayerStr_
private

Layer that holds accumulated probability until now.

Definition at line 122 of file filters.hpp.

double mitre_fast_layered_map::BayesUpdate::probSenseEmpGivenEmp_ {0.8}
private

Definition at line 128 of file filters.hpp.

double mitre_fast_layered_map::BayesUpdate::probSenseEmpGivenOcc_ {0.4}
private

Definition at line 127 of file filters.hpp.

double mitre_fast_layered_map::BayesUpdate::probSenseOccGivenEmpOffset_ {0.3}
private

Definition at line 132 of file filters.hpp.

double mitre_fast_layered_map::BayesUpdate::probSenseOccGivenEmpRate_ {-0.1}
private

Definition at line 131 of file filters.hpp.

double mitre_fast_layered_map::BayesUpdate::probSenseOccGivenOccOffset_ {0.3}
private

Definition at line 130 of file filters.hpp.

double mitre_fast_layered_map::BayesUpdate::probSenseOccGivenOccRate_ {0.1}
private

Definition at line 129 of file filters.hpp.

double mitre_fast_layered_map::BayesUpdate::startingProb_ {0.5}
private

Definition at line 126 of file filters.hpp.


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


mitre_fast_layered_map
Author(s):
autogenerated on Thu Mar 11 2021 03:06:49