$search
00001 /* 00002 * Copyright (c) 2011, Jeannette Bohg and Mårten Björkman 00003 * ({bohg,celle}@csc.kth.se) 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are 00008 * met: 00009 * 00010 * 1.Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * 2.Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * 3.The name of Jeannette Bohg or Mårten Björkman may not be used to 00017 * endorse or promote products derived from this software without 00018 * specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 00023 * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 00024 * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 00025 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 00026 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00027 * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 00028 * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00029 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00030 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 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 // create the marker in the table reference frame 00050 // the caller is responsible for setting the pose of 00051 // the marker to match 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 }