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< T > | fillPolygon (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. | |
| T heatmap::bottomLeftPointPolygon | ( | const geometry_msgs::Polygon & | polygon | ) |
Calculate the point with minimal x, y coordinates of all polygon points.
Extended function
| polygon | Polygon to process |
Definition at line 115 of file geometry_tools.h.
| 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
| polygon | Polygon to process |
| spacing | Spacing between points |
Definition at line 171 of file geometry_tools.h.
| 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.
| point | Point to test |
| polygon | Polygon to test |
Definition at line 75 of file geometry_tools.h.
| double heatmap::pointsDistance | ( | const T & | one, |
| const S & | two | ||
| ) |
Calculate distance between two points.
| one | Point one |
| two | Point two |
Definition at line 34 of file geometry_tools.h.
| bool heatmap::pointsNearby | ( | const T & | one, |
| const S & | two, | ||
| const double & | proximity | ||
| ) |
Evaluate whether two points are approximately adjacent, within a specified proximity distance.
| one | Point one |
| two | Point two |
| proximity | Proximity distance |
Definition at line 64 of file geometry_tools.h.
| double heatmap::polygonPerimeter | ( | const geometry_msgs::Polygon & | polygon | ) |
Calculate polygon perimeter.
| polygon | Polygon to process |
Definition at line 43 of file geometry_tools.h.
| 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
| interpolation_points | Vector of points (coordinates) to interpolate the data at |
| data_points | Vector of points (coordinates) of the input data |
| data | Vector of data entries corresponding to the coordinates in data_points |
| shepard_power | Determines how strong the distance between points is weighted. For more information read the wikipedia article |
Definition at line 204 of file geometry_tools.h.
| T heatmap::topRightPointPolygon | ( | const geometry_msgs::Polygon & | polygon | ) |
Calculate the point with maximal x, y coordinates of all polygon points.
Extended function
| polygon | Polygon to process |
Definition at line 143 of file geometry_tools.h.
| double heatmap::yawOfVector | ( | const T & | origin, |
| const S & | end | ||
| ) |
Calculate the yaw of vector defined by origin and end points.
| origin | Origin point |
| end | End point |
Definition at line 93 of file geometry_tools.h.