Classes | Functions
heatmap Namespace Reference

Classes

class  DistanceMeasure
 Node that requests WIFI signals based on the distance traveled by the robot, visualises them via RViz and provides the possibility to run an interpolation to get a dense map from it. More...
class  HeatmapClient
 Client for FrontierExplorationServer that receives control points from rviz, and creates boundary polygon for frontier exploration. More...
class  Signal
 Class that reads the signal quality of a wifi device and serves it 1. As a topic 2. As a service The actual core functionality is taken from the iwconfig source code. More...
class  SignalSimulator
 Class that simulates a WIFI network with randomly generated signal qualities. It advertises a topic and a service for that. More...

Functions

template<typename T >
T bottomLeftPointPolygon (const geometry_msgs::Polygon &polygon)
 Calculate the point with minimal x, y coordinates of all polygon points.
template<typename T >
std::vector< TfillPolygon (const geometry_msgs::Polygon &polygon, const double spacing)
 Fill a polygon with points known the spacing between them.
template<typename T >
bool pointInPolygon (const T &point, const geometry_msgs::Polygon &polygon)
 Evaluate if point is inside area defined by polygon. Undefined behaviour for points on line.
template<typename T , typename S >
double pointsDistance (const T &one, const S &two)
 Calculate distance between two points.
template<typename T , typename S >
bool pointsNearby (const T &one, const S &two, const double &proximity)
 Evaluate whether two points are approximately adjacent, within a specified proximity distance.
double polygonPerimeter (const geometry_msgs::Polygon &polygon)
 Calculate polygon perimeter.
template<typename T , typename S >
std::vector< double > shepardInterpolation (const std::vector< T > interpolation_points, const std::vector< T > data_points, const std::vector< S > data, const double shepard_power)
 Interpolate a known scattered data set using the Shepard (aka inverse distance weighting) interpolation.
template<typename T >
T topRightPointPolygon (const geometry_msgs::Polygon &polygon)
 Calculate the point with maximal x, y coordinates of all polygon points.
template<typename T , typename S >
double yawOfVector (const T &origin, const S &end)
 Calculate the yaw of vector defined by origin and end points.

Function Documentation

template<typename T >
T heatmap::bottomLeftPointPolygon ( const geometry_msgs::Polygon &  polygon)

Calculate the point with minimal x, y coordinates of all polygon points.

Extended function

Parameters:
polygonPolygon to process
Returns:
Point with minimum x, y coordinates

Definition at line 115 of file geometry_tools.h.

template<typename T >
std::vector<T> heatmap::fillPolygon ( const geometry_msgs::Polygon &  polygon,
const double  spacing 
)

Fill a polygon with points known the spacing between them.

Extended function

Parameters:
polygonPolygon to process
spacingSpacing between points
Returns:
Vector of points

Definition at line 171 of file geometry_tools.h.

template<typename T >
bool heatmap::pointInPolygon ( const T point,
const geometry_msgs::Polygon &  polygon 
)

Evaluate if point is inside area defined by polygon. Undefined behaviour for points on line.

Parameters:
pointPoint to test
polygonPolygon to test
Returns:
True if point is inside polygon, false otherwise

Definition at line 75 of file geometry_tools.h.

template<typename T , typename S >
double heatmap::pointsDistance ( const T one,
const S &  two 
)

Calculate distance between two points.

Parameters:
onePoint one
twoPoint two
Returns:
Distance between two points

Definition at line 34 of file geometry_tools.h.

template<typename T , typename S >
bool heatmap::pointsNearby ( const T one,
const S &  two,
const double &  proximity 
)

Evaluate whether two points are approximately adjacent, within a specified proximity distance.

Parameters:
onePoint one
twoPoint two
proximityProximity distance
Returns:
True if approximately adjacent, false otherwise

Definition at line 64 of file geometry_tools.h.

double heatmap::polygonPerimeter ( const geometry_msgs::Polygon &  polygon)

Calculate polygon perimeter.

Parameters:
polygonPolygon to process
Returns:
Perimeter of polygon

Definition at line 43 of file geometry_tools.h.

template<typename T , typename S >
std::vector<double> heatmap::shepardInterpolation ( const std::vector< T interpolation_points,
const std::vector< T data_points,
const std::vector< S >  data,
const double  shepard_power 
)

Interpolate a known scattered data set using the Shepard (aka inverse distance weighting) interpolation.

Extended function

Parameters:
interpolation_pointsVector of points (coordinates) to interpolate the data at
data_pointsVector of points (coordinates) of the input data
dataVector of data entries corresponding to the coordinates in data_points
shepard_powerDetermines how strong the distance between points is weighted. For more information read the wikipedia article
Returns:
Vector of interpolated data corresponding to the coordinates in interpolation_points

Definition at line 204 of file geometry_tools.h.

template<typename T >
T heatmap::topRightPointPolygon ( const geometry_msgs::Polygon &  polygon)

Calculate the point with maximal x, y coordinates of all polygon points.

Extended function

Parameters:
polygonPolygon to process
Returns:
Point with maximum x, y coordinates

Definition at line 143 of file geometry_tools.h.

template<typename T , typename S >
double heatmap::yawOfVector ( const T origin,
const S &  end 
)

Calculate the yaw of vector defined by origin and end points.

Parameters:
originOrigin point
endEnd point
Returns:
Yaw angle of vector

Definition at line 93 of file geometry_tools.h.



heatmap
Author(s): Adrian Bauer
autogenerated on Thu Feb 11 2016 23:05:26