Public Member Functions | Protected Attributes
HectorMapTools::DistanceMeasurementProvider Class Reference

#include <HectorMapTools.h>

List of all members.

Public Member Functions

int bresenham2D (unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, unsigned int offset, unsigned int max_length)
float checkOccupancyBresenhami (const Eigen::Vector2i &beginMap, const Eigen::Vector2i &endMap, Eigen::Vector2i *hitCoords=0, unsigned int max_length=UINT_MAX)
 DistanceMeasurementProvider ()
float getDist (const Eigen::Vector2f &begin_world, const Eigen::Vector2f &end_world, Eigen::Vector2f *hitCoords=0)
void setMap (const nav_msgs::OccupancyGridConstPtr map)

Protected Attributes

nav_msgs::OccupancyGridConstPtr map_ptr_
CoordinateTransformer< float > world_map_transformer_

Detailed Description

Definition at line 118 of file HectorMapTools.h.


Constructor & Destructor Documentation

Definition at line 121 of file HectorMapTools.h.


Member Function Documentation

int HectorMapTools::DistanceMeasurementProvider::bresenham2D ( unsigned int  abs_da,
unsigned int  abs_db,
int  error_b,
int  offset_a,
int  offset_b,
unsigned int  offset,
unsigned int  max_length 
) [inline]

Definition at line 212 of file HectorMapTools.h.

float HectorMapTools::DistanceMeasurementProvider::checkOccupancyBresenhami ( const Eigen::Vector2i &  beginMap,
const Eigen::Vector2i &  endMap,
Eigen::Vector2i *  hitCoords = 0,
unsigned int  max_length = UINT_MAX 
) [inline]

Definition at line 148 of file HectorMapTools.h.

float HectorMapTools::DistanceMeasurementProvider::getDist ( const Eigen::Vector2f &  begin_world,
const Eigen::Vector2f &  end_world,
Eigen::Vector2f *  hitCoords = 0 
) [inline]

Definition at line 133 of file HectorMapTools.h.

void HectorMapTools::DistanceMeasurementProvider::setMap ( const nav_msgs::OccupancyGridConstPtr  map) [inline]

Definition at line 126 of file HectorMapTools.h.


Member Data Documentation

nav_msgs::OccupancyGridConstPtr HectorMapTools::DistanceMeasurementProvider::map_ptr_ [protected]

Definition at line 236 of file HectorMapTools.h.

Definition at line 235 of file HectorMapTools.h.


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


hector_map_tools
Author(s): Stefan Kohlbrecher
autogenerated on Wed Aug 26 2015 11:44:51