Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #include "grid_map_ros/PolygonRosConverter.hpp"
00009
00010
00011 #include <geometry_msgs/Point32.h>
00012
00013 namespace grid_map {
00014
00015 PolygonRosConverter::PolygonRosConverter() {}
00016
00017 PolygonRosConverter::~PolygonRosConverter() {}
00018
00019 void PolygonRosConverter::toMessage(const grid_map::Polygon& polygon, geometry_msgs::PolygonStamped& message)
00020 {
00021 message.header.stamp.fromNSec(polygon.getTimestamp());
00022 message.header.frame_id = polygon.getFrameId();
00023
00024 for (const auto& vertex : polygon.getVertices()) {
00025 geometry_msgs::Point32 point;
00026 point.x = vertex.x();
00027 point.y = vertex.y();
00028 point.z = 0.0;
00029 message.polygon.points.push_back(point);
00030 }
00031 }
00032
00033 void PolygonRosConverter::toLineMarker(const grid_map::Polygon& polygon, const std_msgs::ColorRGBA& color, const double lineWidth,
00034 const double zCoordinate, visualization_msgs::Marker& marker)
00035 {
00036 marker.header.stamp.fromNSec(polygon.getTimestamp());
00037 marker.header.frame_id = polygon.getFrameId();
00038 marker.lifetime = ros::Duration(0.0);
00039 marker.action = visualization_msgs::Marker::ADD;
00040 marker.type = visualization_msgs::Marker::LINE_STRIP;
00041 marker.color = color;
00042 marker.scale.x = lineWidth;
00043
00044 unsigned int startIndex = marker.points.size();
00045 unsigned int nVertices = polygon.nVertices() + 1;
00046 unsigned int nTotalVertices = marker.points.size() + nVertices;
00047 marker.points.resize(nTotalVertices);
00048 marker.colors.resize(nTotalVertices, color);
00049
00050 unsigned int i = startIndex;
00051 for( ; i < nTotalVertices - 1; i++) {
00052 marker.points[i].x = polygon[i].x();
00053 marker.points[i].y = polygon[i].y();
00054 marker.points[i].z = zCoordinate;
00055 }
00056 marker.points[i].x = marker.points[startIndex].x;
00057 marker.points[i].y = marker.points[startIndex].y;
00058 marker.points[i].z = marker.points[startIndex].z;
00059 }
00060
00061 void PolygonRosConverter::toTriangleListMarker(const grid_map::Polygon& polygon, const std_msgs::ColorRGBA& color,
00062 const double zCoordinate, visualization_msgs::Marker& marker)
00063 {
00064 marker.header.stamp.fromNSec(polygon.getTimestamp());
00065 marker.header.frame_id = polygon.getFrameId();
00066 marker.lifetime = ros::Duration(0.0);
00067 marker.action = visualization_msgs::Marker::ADD;
00068 marker.type = visualization_msgs::Marker::TRIANGLE_LIST;
00069 marker.scale.x = 1.0;
00070 marker.scale.y = 1.0;
00071 marker.scale.z = 1.0;
00072 marker.color = color;
00073
00074 std::vector<Polygon> polygons = polygon.triangulate();
00075 if (polygons.size() < 1) return;
00076
00077 size_t nPoints = 3 * polygons.size();
00078 marker.points.resize(nPoints);
00079 marker.colors.resize(polygons.size(), color);
00080
00081 for (size_t i = 0; i < polygons.size(); ++i) {
00082 for (size_t j = 0; j < 3; ++j) {
00083 const size_t pointIndex = 3 * i + j;
00084 marker.points[pointIndex].x = polygons[i].getVertex(j).x();
00085 marker.points[pointIndex].y = polygons[i].getVertex(j).y();
00086 marker.points[pointIndex].z = zCoordinate;
00087 }
00088 }
00089 }
00090
00091 }