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...
Public Member Functions | |
| DistanceMeasure () | |
Private Member Functions | |
| double | convertSignalToColor (heatmap::wifi_signal &signal) |
| Converts a signal quality value to a color value used for RViz markers. | |
| std::vector< double > | interpolateAndVisualize (std::vector< geometry_msgs::Point32 > &measure_points, std::vector< int > &measure_data, geometry_msgs::Polygon &poly, double interpolation_spacing, double shepard_power) |
| Processes a list of measuring data, interpolates it and visualizes it in RViz. | |
| void | polygonCallback (const geometry_msgs::PolygonStamped &poly) |
| visualization_msgs::Marker | prepareSphereMarker (double color_g, double sphere_size, tf::Vector3 &pos) |
| Creates a sphere RViz marker for publishing. | |
| bool | startInterpolation (heatmap::interpolation_service::Request &req, heatmap::interpolation_service::Response &res) |
Private Attributes | |
| int | av_sig |
| heatmap::wifi_signal | current_sig |
| std::vector< int > | data_list |
| ros::Publisher | interpol_marker_pub |
| int | marker_id |
| ros::Publisher | marker_pub |
| std::vector< tf::Vector3 > | measure_list |
| ros::NodeHandle | n |
| geometry_msgs::PolygonStamped | polygon |
| int | quality_max |
| int | sig_count |
| ros::Subscriber | signal_sub |
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.
Definition at line 34 of file distance_measure.cpp.
| heatmap::DistanceMeasure::DistanceMeasure | ( | ) | [inline] |
Definition at line 183 of file distance_measure.cpp.
| double heatmap::DistanceMeasure::convertSignalToColor | ( | heatmap::wifi_signal & | signal | ) | [inline, private] |
Converts a signal quality value to a color value used for RViz markers.
| signal | Signal to convert |
Definition at line 53 of file distance_measure.cpp.
| std::vector<double> heatmap::DistanceMeasure::interpolateAndVisualize | ( | std::vector< geometry_msgs::Point32 > & | measure_points, |
| std::vector< int > & | measure_data, | ||
| geometry_msgs::Polygon & | poly, | ||
| double | interpolation_spacing, | ||
| double | shepard_power | ||
| ) | [inline, private] |
Processes a list of measuring data, interpolates it and visualizes it in RViz.
| measure_points | List of measuring points (x, y coordinates) |
| measure_data | List of measuring data according to measure_points |
| poly | Polygon specifying the measuring area |
| interpolation_spacing | The space between the interpolated points |
| shepard_power | Determines how strong the distance between points is weighted. For more information read the wikipedia article |
Definition at line 118 of file distance_measure.cpp.
| void heatmap::DistanceMeasure::polygonCallback | ( | const geometry_msgs::PolygonStamped & | poly | ) | [inline, private] |
Definition at line 176 of file distance_measure.cpp.
| visualization_msgs::Marker heatmap::DistanceMeasure::prepareSphereMarker | ( | double | color_g, |
| double | sphere_size, | ||
| tf::Vector3 & | pos | ||
| ) | [inline, private] |
Creates a sphere RViz marker for publishing.
| color_g | The color for the marker, in range of 0 to 1, 0 is pure red, 1 is pure green |
| sphere_size | The radius of the sphere |
| pos | The position of the marker on the map |
Definition at line 71 of file distance_measure.cpp.
| bool heatmap::DistanceMeasure::startInterpolation | ( | heatmap::interpolation_service::Request & | req, |
| heatmap::interpolation_service::Response & | res | ||
| ) | [inline, private] |
Definition at line 154 of file distance_measure.cpp.
int heatmap::DistanceMeasure::av_sig [private] |
Definition at line 40 of file distance_measure.cpp.
heatmap::wifi_signal heatmap::DistanceMeasure::current_sig [private] |
Definition at line 37 of file distance_measure.cpp.
std::vector<int> heatmap::DistanceMeasure::data_list [private] |
Definition at line 43 of file distance_measure.cpp.
Definition at line 38 of file distance_measure.cpp.
int heatmap::DistanceMeasure::marker_id [private] |
Definition at line 44 of file distance_measure.cpp.
Definition at line 38 of file distance_measure.cpp.
std::vector<tf::Vector3> heatmap::DistanceMeasure::measure_list [private] |
Definition at line 42 of file distance_measure.cpp.
ros::NodeHandle heatmap::DistanceMeasure::n [private] |
Definition at line 45 of file distance_measure.cpp.
geometry_msgs::PolygonStamped heatmap::DistanceMeasure::polygon [private] |
Definition at line 41 of file distance_measure.cpp.
int heatmap::DistanceMeasure::quality_max [private] |
Definition at line 46 of file distance_measure.cpp.
int heatmap::DistanceMeasure::sig_count [private] |
Definition at line 40 of file distance_measure.cpp.
Definition at line 39 of file distance_measure.cpp.