util.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef UTIL_H_
29 #define UTIL_H_
30 
31 
32 #include <android/log.h>
36 #include <tango-gl/util.h>
37 #include <pcl/point_cloud.h>
38 #include <pcl/point_types.h>
39 #include <pcl/Vertices.h>
40 #include <pcl/pcl_base.h>
41 
42 class LogHandler : public UEventsHandler
43 {
44 public:
46  {
50 
52  }
53 protected:
54  virtual bool handleEvent(UEvent * event)
55  {
56  if(event->getClassName().compare("ULogEvent") == 0)
57  {
58  ULogEvent * logEvent = (ULogEvent*)event;
59  if(logEvent->getCode() == ULogger::kDebug)
60  {
61  LOGD(logEvent->getMsg().c_str());
62  }
63  else if(logEvent->getCode() == ULogger::kInfo)
64  {
65  LOGI(logEvent->getMsg().c_str());
66  }
67  else if(logEvent->getCode() == ULogger::kWarning)
68  {
69  LOGW(logEvent->getMsg().c_str());
70  }
71  else if(logEvent->getCode() >= ULogger::kError)
72  {
73  LOGE(logEvent->getMsg().c_str());
74  }
75 
76  }
77  return false;
78  }
79 };
80 
82  1.0f, 0.0f, 0.0f, 0.0f,
83  0.0f, 0.0f, 1.0f, 0.0f,
84  0.0f, -1.0f, 0.0f, 0.0f);
85 
87  0.0f, 1.0f, 0.0f, 0.0f,
88  -1.0f, 0.0f, 0.0f, 0.0f,
89  0.0f, 0.0f, 1.0f, 0.0f);
90 
92  0.0f, -1.0f, 0.0f, 0.0f,
93  0.0f, 0.0f, 1.0f, 0.0f,
94  -1.0f, 0.0f, 0.0f, 0.0f);
95 
97  0.0f, -1.0f, 0.0f, 0.0f,
98  0.0f, 0.0f, 1.0f, 0.0f,
99  -1.0f, 0.0f, 0.0f, 0.0f);
100 
102  0.0f, 0.0f, -1.0f, 0.0f,
103  -1.0f, 0.0f, 0.0f, 0.0f,
104  0.0f, 1.0f, 0.0f, 0.0f);
105 
107 {
108  glm::mat4 mat(1.0f);
109  // gl is column wise
110  mat[0][0] = transform(0,0);
111  mat[1][0] = transform(0,1);
112  mat[2][0] = transform(0,2);
113  mat[0][1] = transform(1,0);
114  mat[1][1] = transform(1,1);
115  mat[2][1] = transform(1,2);
116  mat[0][2] = transform(2,0);
117  mat[1][2] = transform(2,1);
118  mat[2][2] = transform(2,2);
119 
120  mat[3][0] = transform(0,3);
121  mat[3][1] = transform(1,3);
122  mat[3][2] = transform(2,3);
123  return mat;
124 }
125 
127 {
128  rtabmap::Transform transform;
129  // gl is column wise
130  transform(0,0) = mat[0][0];
131  transform(0,1) = mat[1][0];
132  transform(0,2) = mat[2][0];
133  transform(1,0) = mat[0][1];
134  transform(1,1) = mat[1][1];
135  transform(1,2) = mat[2][1];
136  transform(2,0) = mat[0][2];
137  transform(2,1) = mat[1][2];
138  transform(2,2) = mat[2][2];
139 
140  transform(0,3) = mat[3][0];
141  transform(1,3) = mat[3][1];
142  transform(2,3) = mat[3][2];
143 
144  return transform;
145 }
146 
147 class Mesh
148 {
149 public:
150  Mesh() :
151  cloud(new pcl::PointCloud<pcl::PointXYZRGB>),
152  normals(new pcl::PointCloud<pcl::Normal>),
153  indices(new std::vector<int>),
154  visible(true)
155  {
156  gains[0] = gains[1] = gains[2] = 1.0f;
157  }
158 
159  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud; // organized cloud
160  pcl::PointCloud<pcl::Normal>::Ptr normals;
161  pcl::IndicesPtr indices;
162  std::vector<pcl::Vertices> polygons;
163  std::vector<pcl::Vertices> polygonsLowRes;
164  rtabmap::Transform pose; // in rtabmap coordinates
165  bool visible;
167  double gains[3]; // RGB gains
168 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
169  std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > texCoords;
170 #else
171  std::vector<Eigen::Vector2f> texCoords;
172 #endif
173  cv::Mat texture;
174 };
175 
176 #endif /* UTIL_H_ */
int getCode() const
Definition: UEvent.h:74
static void setPrintThreadId(bool printThreadId)
Definition: ULogger.h:309
#define LOGW(...)
Definition: UEvent.h:57
f
Definition: CameraRGBD.h:59
static const rtabmap::Transform rtabmap_world_T_tango_world(0.0f, 1.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f)
Definition: util.h:147
pcl::PointCloud< pcl::Normal >::Ptr normals
Definition: util.h:160
std::vector< pcl::Vertices > polygons
Definition: util.h:162
glm::mat4 glmFromTransform(const rtabmap::Transform &transform)
Definition: util.h:106
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud
Definition: util.h:159
#define LOGE(...)
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
std::vector< pcl::Vertices > polygonsLowRes
Definition: util.h:163
#define LOGD(...)
#define true
Definition: ConvertUTF.c:57
virtual std::string getClassName() const =0
LogHandler()
Definition: util.h:45
static void setEventLevel(ULogger::Level eventSentLevel)
Definition: ULogger.h:348
static const rtabmap::Transform opengl_world_T_rtabmap_world(0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f)
rtabmap::Transform pose
Definition: util.h:164
static const rtabmap::Transform rtabmap_device_T_opengl_device(0.0f, 0.0f,-1.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f)
#define LOGI(...)
static const rtabmap::Transform opengl_world_T_tango_world(1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f)
void registerToEventsManager()
cv::Mat texture
Definition: util.h:173
ULogger class and convenient macros.
bool visible
Definition: util.h:165
virtual bool handleEvent(UEvent *event)
Definition: util.h:54
static const rtabmap::Transform tango_device_T_rtabmap_device(0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f)
Mesh()
Definition: util.h:150
rtabmap::Transform glmToTransform(const glm::mat4 &mat)
Definition: util.h:126
pcl::IndicesPtr indices
Definition: util.h:161
const std::string & getMsg() const
Definition: ULogger.h:137
std::vector< Eigen::Vector2f > texCoords
Definition: util.h:171
rtabmap::CameraModel cameraModel
Definition: util.h:166


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:40