bounding_box_drawable.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007  * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009  * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012  * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #ifndef BOUNDING_BOX_DRAWABLE_H_
00029 #define BOUNDING_BOX_DRAWABLE_H_
00030 
00031 #include "tango-gl/line.h"
00032 
00033 class BoundingBoxDrawable : public tango_gl::Line
00034 {
00035 public:
00036         BoundingBoxDrawable() :
00037                 Line(3.0f, GL_LINES)
00038         {
00039                 vec_vertices_.resize(24);
00040         }
00041 
00042         void updateVertices(const pcl::PointXYZ & min, const pcl::PointXYZ & max)
00043         {
00044                 int index = 0;
00045                 vec_vertices_[index].x = min.x;
00046                 vec_vertices_[index].y = min.y;
00047                 vec_vertices_[index++].z = min.z;
00048                 vec_vertices_[index].x = min.x;
00049                 vec_vertices_[index].y = max.y;
00050                 vec_vertices_[index++].z = min.z;
00051 
00052                 vec_vertices_[index].x = min.x;
00053                 vec_vertices_[index].y = min.y;
00054                 vec_vertices_[index++].z = min.z;
00055                 vec_vertices_[index].x = max.x;
00056                 vec_vertices_[index].y = min.y;
00057                 vec_vertices_[index++].z = min.z;
00058 
00059                 vec_vertices_[index].x = min.x;
00060                 vec_vertices_[index].y = min.y;
00061                 vec_vertices_[index++].z = min.z;
00062                 vec_vertices_[index].x = min.x;
00063                 vec_vertices_[index].y = min.y;
00064                 vec_vertices_[index++].z = max.z;
00065 
00066                 vec_vertices_[index].x = max.x;
00067                 vec_vertices_[index].y = max.y;
00068                 vec_vertices_[index++].z = max.z;
00069                 vec_vertices_[index].x = max.x;
00070                 vec_vertices_[index].y = min.y;
00071                 vec_vertices_[index++].z = max.z;
00072 
00073                 vec_vertices_[index].x = max.x;
00074                 vec_vertices_[index].y = max.y;
00075                 vec_vertices_[index++].z = max.z;
00076                 vec_vertices_[index].x = min.x;
00077                 vec_vertices_[index].y = max.y;
00078                 vec_vertices_[index++].z = max.z;
00079 
00080                 vec_vertices_[index].x = max.x;
00081                 vec_vertices_[index].y = max.y;
00082                 vec_vertices_[index++].z = max.z;
00083                 vec_vertices_[index].x = max.x;
00084                 vec_vertices_[index].y = max.y;
00085                 vec_vertices_[index++].z = min.z;
00086 
00087                 vec_vertices_[index].x = max.x;
00088                 vec_vertices_[index].y = min.y;
00089                 vec_vertices_[index++].z = min.z;
00090                 vec_vertices_[index].x = max.x;
00091                 vec_vertices_[index].y = min.y;
00092                 vec_vertices_[index++].z = max.z;
00093 
00094                 vec_vertices_[index].x = max.x;
00095                 vec_vertices_[index].y = min.y;
00096                 vec_vertices_[index++].z = min.z;
00097                 vec_vertices_[index].x = max.x;
00098                 vec_vertices_[index].y = max.y;
00099                 vec_vertices_[index++].z = min.z;
00100 
00101                 vec_vertices_[index].x = min.x;
00102                 vec_vertices_[index].y = max.y;
00103                 vec_vertices_[index++].z = min.z;
00104                 vec_vertices_[index].x = max.x;
00105                 vec_vertices_[index].y = max.y;
00106                 vec_vertices_[index++].z = min.z;
00107 
00108                 vec_vertices_[index].x = min.x;
00109                 vec_vertices_[index].y = max.y;
00110                 vec_vertices_[index++].z = min.z;
00111                 vec_vertices_[index].x = min.x;
00112                 vec_vertices_[index].y = max.y;
00113                 vec_vertices_[index++].z = max.z;
00114 
00115                 vec_vertices_[index].x = min.x;
00116                 vec_vertices_[index].y = min.y;
00117                 vec_vertices_[index++].z = max.z;
00118                 vec_vertices_[index].x = max.x;
00119                 vec_vertices_[index].y = min.y;
00120                 vec_vertices_[index++].z = max.z;
00121 
00122                 vec_vertices_[index].x = min.x;
00123                 vec_vertices_[index].y = min.y;
00124                 vec_vertices_[index++].z = max.z;
00125                 vec_vertices_[index].x = min.x;
00126                 vec_vertices_[index].y = max.y;
00127                 vec_vertices_[index++].z = max.z;
00128         }
00129 
00130 };
00131 #endif  // TANGO_GL_LINE_H_


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:18