Defines a keypoint in metric coordinates of the map. More...
#include <costmap_to_polygons.h>
| Public Member Functions | |
| KeyPoint () | |
| Default constructor.  More... | |
| KeyPoint (double x_, double y_) | |
| Constructor with point initialization.  More... | |
| void | toPointMsg (geometry_msgs::Point &point) const | 
| Convert keypoint to geometry_msgs::Point message type.  More... | |
| void | toPointMsg (geometry_msgs::Point32 &point) const | 
| Convert keypoint to geometry_msgs::Point32 message type.  More... | |
| Public Attributes | |
| double | x | 
| x coordinate [m]  More... | |
| double | y | 
| y coordinate [m]  More... | |
Defines a keypoint in metric coordinates of the map.
Definition at line 87 of file costmap_to_polygons.h.
| 
 | inline | 
Default constructor.
Definition at line 90 of file costmap_to_polygons.h.
| 
 | inline | 
Constructor with point initialization.
Definition at line 92 of file costmap_to_polygons.h.
| 
 | inline | 
Convert keypoint to geometry_msgs::Point message type.
Definition at line 97 of file costmap_to_polygons.h.
| 
 | inline | 
Convert keypoint to geometry_msgs::Point32 message type.
Definition at line 99 of file costmap_to_polygons.h.
| double costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint::x | 
x coordinate [m]
Definition at line 93 of file costmap_to_polygons.h.
| double costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint::y | 
y coordinate [m]
Definition at line 94 of file costmap_to_polygons.h.