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

#include <filters.hpp>

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

Public Member Functions

virtual bool configure ()
 
 RayTrace2d ()
 
bool trace (grid_map::GridMap &_map, const grid_map::Index &start, const grid_map::Index &end)
 
virtual bool update (const grid_map::GridMap &_mapIn, grid_map::GridMap &_mapOut)
 
virtual ~RayTrace2d ()
 
- 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

std::string groundLayer_
 Layer for setting ground plane points. More...
 
std::string mode_
 Production or testing. If testing mode will throw errors if calculations break bounds. More...
 
std::string nongroundLayer_
 blocking rays More...
 

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

Draws rays from the center of the grid map to each of the outside squares and calculates if an obstacle is blocking the way. From this it can calculate if certain squares are clear, blocked, or unknown.

Definition at line 86 of file filters.hpp.

Constructor & Destructor Documentation

mitre_fast_layered_map::RayTrace2d::RayTrace2d ( )

Definition at line 17 of file ray_trace_2d.cpp.

mitre_fast_layered_map::RayTrace2d::~RayTrace2d ( )
virtual

Definition at line 21 of file ray_trace_2d.cpp.

Member Function Documentation

bool mitre_fast_layered_map::RayTrace2d::configure ( )
virtual

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

Definition at line 25 of file ray_trace_2d.cpp.

bool mitre_fast_layered_map::RayTrace2d::trace ( grid_map::GridMap _map,
const grid_map::Index start,
const grid_map::Index end 
)

Definition at line 120 of file ray_trace_2d.cpp.

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

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

Definition at line 49 of file ray_trace_2d.cpp.

Member Data Documentation

std::string mitre_fast_layered_map::RayTrace2d::groundLayer_
private

Layer for setting ground plane points.

Definition at line 102 of file filters.hpp.

std::string mitre_fast_layered_map::RayTrace2d::mode_
private

Production or testing. If testing mode will throw errors if calculations break bounds.

Definition at line 103 of file filters.hpp.

std::string mitre_fast_layered_map::RayTrace2d::nongroundLayer_
private

blocking rays

Layer that holds non ground points. Will be used to check objects

Definition at line 100 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