Public Member Functions | Static Public Member Functions | List of all members
grid_map::PolygonRosConverter Class Reference

#include <PolygonRosConverter.hpp>

Public Member Functions

 PolygonRosConverter ()
 
virtual ~PolygonRosConverter ()
 

Static Public Member Functions

static void toLineMarker (const grid_map::Polygon &polygon, const std_msgs::ColorRGBA &color, const double lineWidth, const double zCoordinate, visualization_msgs::Marker &marker)
 
static void toMessage (const grid_map::Polygon &polygon, geometry_msgs::PolygonStamped &message)
 
static void toTriangleListMarker (const grid_map::Polygon &polygon, const std_msgs::ColorRGBA &color, const double zCoordinate, visualization_msgs::Marker &marker)
 

Detailed Description

Definition at line 24 of file PolygonRosConverter.hpp.

Constructor & Destructor Documentation

grid_map::PolygonRosConverter::PolygonRosConverter ( )

Default constructor.

Definition at line 15 of file PolygonRosConverter.cpp.

grid_map::PolygonRosConverter::~PolygonRosConverter ( )
virtual

Constructor with vertices.

Parameters
verticesthe points of the polygon.

Definition at line 17 of file PolygonRosConverter.cpp.

Member Function Documentation

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]polygonthe polygon object.
[in]colorthe desired color of the marker.
[in]lineWidththe with of the line marker.
[in]zCoordinatez-coordinate of the planar polygon.
[out]markerthe 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]polygonthe polygon object.
[out]messagethe 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]polygonthe polygon object.
[in]colorthe desired color of the marker.
[in]zCoordinatez-coordinate of the planar polygon.
[out]markerthe 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:


grid_map_ros
Author(s): Péter Fankhauser
autogenerated on Tue Jun 1 2021 02:13:35