Public Member Functions | Public Attributes
costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint Struct Reference

Defines a keypoint in metric coordinates of the map. More...

#include <costmap_to_polygons.h>

List of all members.

Public Member Functions

 KeyPoint ()
 Default constructor.
 KeyPoint (double x_, double y_)
 Constructor with point initialization.
void toPointMsg (geometry_msgs::Point &point) const
 Convert keypoint to geometry_msgs::Point message type.
void toPointMsg (geometry_msgs::Point32 &point) const
 Convert keypoint to geometry_msgs::Point32 message type.

Public Attributes

double x
 x coordinate [m]
double y
 y coordinate [m]

Detailed Description

Defines a keypoint in metric coordinates of the map.

Definition at line 87 of file costmap_to_polygons.h.


Constructor & Destructor Documentation

Default constructor.

Definition at line 90 of file costmap_to_polygons.h.

costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint::KeyPoint ( double  x_,
double  y_ 
) [inline]

Constructor with point initialization.

Definition at line 92 of file costmap_to_polygons.h.


Member Function Documentation

void costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint::toPointMsg ( geometry_msgs::Point &  point) const [inline]

Convert keypoint to geometry_msgs::Point message type.

Definition at line 97 of file costmap_to_polygons.h.

void costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint::toPointMsg ( geometry_msgs::Point32 &  point) const [inline]

Convert keypoint to geometry_msgs::Point32 message type.

Definition at line 99 of file costmap_to_polygons.h.


Member Data Documentation

x coordinate [m]

Definition at line 93 of file costmap_to_polygons.h.

y coordinate [m]

Definition at line 94 of file costmap_to_polygons.h.


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


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Wed Sep 20 2017 03:00:37