util.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 UTIL_H_
00029 #define UTIL_H_
00030 
00031 
00032 #include <android/log.h>
00033 #include <rtabmap/utilite/UEventsHandler.h>
00034 #include <rtabmap/utilite/ULogger.h>
00035 #include <rtabmap/core/CameraModel.h>
00036 #include <tango-gl/util.h>
00037 #include <pcl/point_cloud.h>
00038 #include <pcl/point_types.h>
00039 #include <pcl/Vertices.h>
00040 #include <pcl/pcl_base.h>
00041 
00042 class LogHandler : public UEventsHandler
00043 {
00044 public:
00045         LogHandler()
00046         {
00047                 ULogger::setLevel(ULogger::kDebug);
00048                 ULogger::setEventLevel(ULogger::kDebug);
00049                 ULogger::setPrintThreadId(true);
00050 
00051                 registerToEventsManager();
00052         }
00053 protected:
00054         virtual bool handleEvent(UEvent * event)
00055         {
00056                 if(event->getClassName().compare("ULogEvent") == 0)
00057                 {
00058                         ULogEvent * logEvent = (ULogEvent*)event;
00059                         if(logEvent->getCode() == ULogger::kDebug)
00060                         {
00061                                 LOGD(logEvent->getMsg().c_str());
00062                         }
00063                         else if(logEvent->getCode() == ULogger::kInfo)
00064                         {
00065                                 LOGI(logEvent->getMsg().c_str());
00066                         }
00067                         else if(logEvent->getCode() == ULogger::kWarning)
00068                         {
00069                                 LOGW(logEvent->getMsg().c_str());
00070                         }
00071                         else if(logEvent->getCode() >= ULogger::kError)
00072                         {
00073                                 LOGE(logEvent->getMsg().c_str());
00074                         }
00075 
00076                 }
00077                 return false;
00078         }
00079 };
00080 
00081 static const rtabmap::Transform opengl_world_T_tango_world(
00082                 1.0f,  0.0f,  0.0f, 0.0f,
00083                 0.0f,  0.0f,  1.0f, 0.0f,
00084                 0.0f, -1.0f,  0.0f, 0.0f);
00085 
00086 static const rtabmap::Transform rtabmap_world_T_tango_world(
00087                  0.0f, 1.0f, 0.0f, 0.0f,
00088             -1.0f, 0.0f, 0.0f, 0.0f,
00089                  0.0f, 0.0f, 1.0f, 0.0f);
00090 
00091 static const rtabmap::Transform tango_device_T_rtabmap_device(
00092                  0.0f, -1.0f, 0.0f, 0.0f,
00093              0.0f,  0.0f, 1.0f, 0.0f,
00094                 -1.0f,  0.0f, 0.0f, 0.0f);
00095 
00096 static const rtabmap::Transform opengl_world_T_rtabmap_world(
00097                  0.0f, -1.0f, 0.0f, 0.0f,
00098                  0.0f,  0.0f, 1.0f, 0.0f,
00099                 -1.0f,  0.0f, 0.0f, 0.0f);
00100 
00101 static const rtabmap::Transform rtabmap_device_T_opengl_device(
00102                  0.0f, 0.0f, -1.0f, 0.0f,
00103                 -1.0f, 0.0f,  0.0f, 0.0f,
00104                  0.0f, 1.0f,  0.0f, 0.0f);
00105 
00106 inline glm::mat4 glmFromTransform(const rtabmap::Transform & transform)
00107 {
00108         glm::mat4 mat(1.0f);
00109         // gl is column wise
00110         mat[0][0] = transform(0,0);
00111         mat[1][0] = transform(0,1);
00112         mat[2][0] = transform(0,2);
00113         mat[0][1] = transform(1,0);
00114         mat[1][1] = transform(1,1);
00115         mat[2][1] = transform(1,2);
00116         mat[0][2] = transform(2,0);
00117         mat[1][2] = transform(2,1);
00118         mat[2][2] = transform(2,2);
00119 
00120         mat[3][0] = transform(0,3);
00121         mat[3][1] = transform(1,3);
00122         mat[3][2] = transform(2,3);
00123         return mat;
00124 }
00125 
00126 inline rtabmap::Transform glmToTransform(const glm::mat4 & mat)
00127 {
00128         rtabmap::Transform transform;
00129         // gl is column wise
00130         transform(0,0) = mat[0][0];
00131         transform(0,1) = mat[1][0];
00132         transform(0,2) = mat[2][0];
00133         transform(1,0) = mat[0][1];
00134         transform(1,1) = mat[1][1];
00135         transform(1,2) = mat[2][1];
00136         transform(2,0) = mat[0][2];
00137         transform(2,1) = mat[1][2];
00138         transform(2,2) = mat[2][2];
00139 
00140         transform(0,3) = mat[3][0];
00141         transform(1,3) = mat[3][1];
00142         transform(2,3) = mat[3][2];
00143 
00144         return transform;
00145 }
00146 
00147 class Mesh
00148 {
00149 public:
00150         Mesh() :
00151                 cloud(new pcl::PointCloud<pcl::PointXYZRGB>),
00152                 normals(new pcl::PointCloud<pcl::Normal>),
00153                 indices(new std::vector<int>),
00154                 visible(true)
00155         {
00156                 gains[0] = gains[1] = gains[2] = 1.0f;
00157         }
00158 
00159         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud; // organized cloud
00160         pcl::PointCloud<pcl::Normal>::Ptr normals;
00161         pcl::IndicesPtr indices;
00162         std::vector<pcl::Vertices> polygons;
00163         std::vector<pcl::Vertices> polygonsLowRes;
00164         rtabmap::Transform pose; // in rtabmap coordinates
00165         bool visible;
00166         rtabmap::CameraModel cameraModel;
00167         double gains[3]; // RGB gains
00168 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00169         std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > texCoords;
00170 #else
00171         std::vector<Eigen::Vector2f> texCoords;
00172 #endif
00173         cv::Mat texture;
00174 };
00175 
00176 #endif /* UTIL_H_ */


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