Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include <visualization_msgs/Marker.h>
00034 #include <geometry_msgs/Point32.h>
00035
00036 namespace fast_plane_detection {
00037
00038 visualization_msgs::Marker
00039 getPlaneMarker( geometry_msgs::Point32 top_left,
00040 geometry_msgs::Point32 top_right,
00041 geometry_msgs::Point32 bottom_left,
00042 geometry_msgs::Point32 bottom_right)
00043 {
00044 visualization_msgs::Marker marker;
00045 marker.action = visualization_msgs::Marker::ADD;
00046 marker.type = visualization_msgs::Marker::LINE_STRIP;
00047 marker.lifetime = ros::Duration();
00048
00049
00050
00051
00052
00053 marker.scale.x = 0.001;
00054 marker.scale.y = 0.001;
00055 marker.scale.z = 0.001;
00056
00057 marker.points.resize(5);
00058 marker.points[0].x = top_left.x;
00059 marker.points[0].y = top_left.y;
00060 marker.points[0].z = 0;
00061
00062 marker.points[1].x = top_right.x;
00063 marker.points[1].y = top_right.y;
00064 marker.points[1].z = 0;
00065
00066 marker.points[2].x = bottom_right.x;
00067 marker.points[2].y = bottom_right.y;
00068 marker.points[2].z = 0;
00069
00070 marker.points[3].x = bottom_left.x;
00071 marker.points[3].y = bottom_left.y;
00072 marker.points[3].z = 0;
00073
00074 marker.points[4].x = top_left.x;
00075 marker.points[4].y = top_left.y;
00076 marker.points[4].z = 0;
00077
00078 marker.points.resize(6);
00079 marker.points[5].x = top_left.x;
00080 marker.points[5].y = top_left.y;
00081 marker.points[5].z = 0.02;
00082
00083 marker.color.r = 1.0;
00084 marker.color.g = 1.0;
00085 marker.color.b = 0.0;
00086 marker.color.a = 1.0;
00087
00088 return marker;
00089 }
00090
00091 }