#include <PolygonRosConverter.hpp>
Definition at line 24 of file PolygonRosConverter.hpp.
grid_map::PolygonRosConverter::PolygonRosConverter |
( |
| ) |
|
grid_map::PolygonRosConverter::~PolygonRosConverter |
( |
| ) |
|
|
virtual |
Constructor with vertices.
- Parameters
-
vertices | the points of the polygon. |
Definition at line 17 of file PolygonRosConverter.cpp.
void grid_map::PolygonRosConverter::toLineMarker |
( |
const grid_map::Polygon & |
polygon, |
|
|
const std_msgs::ColorRGBA & |
color, |
|
|
const double |
lineWidth, |
|
|
const double |
zCoordinate, |
|
|
visualization_msgs::Marker & |
marker |
|
) |
| |
|
static |
Converts a polygon object to a ROS line strip marker message.
- Parameters
-
[in] | polygon | the polygon object. |
[in] | color | the desired color of the marker. |
[in] | lineWidth | the with of the line marker. |
[in] | zCoordinate | z-coordinate of the planar polygon. |
[out] | marker | the ROS marker message to be populated. |
Definition at line 33 of file PolygonRosConverter.cpp.
void grid_map::PolygonRosConverter::toMessage |
( |
const grid_map::Polygon & |
polygon, |
|
|
geometry_msgs::PolygonStamped & |
message |
|
) |
| |
|
static |
Converts a polygon object to a ROS PolygonStamped message.
- Parameters
-
[in] | polygon | the polygon object. |
[out] | message | the ROS PolygonStamped message to be populated. |
Definition at line 19 of file PolygonRosConverter.cpp.
void grid_map::PolygonRosConverter::toTriangleListMarker |
( |
const grid_map::Polygon & |
polygon, |
|
|
const std_msgs::ColorRGBA & |
color, |
|
|
const double |
zCoordinate, |
|
|
visualization_msgs::Marker & |
marker |
|
) |
| |
|
static |
Converts a polygon object to a ROS triangle list marker message.
- Parameters
-
[in] | polygon | the polygon object. |
[in] | color | the desired color of the marker. |
[in] | zCoordinate | z-coordinate of the planar polygon. |
[out] | marker | the ROS marker message to be populated. |
Definition at line 61 of file PolygonRosConverter.cpp.
The documentation for this class was generated from the following files: