35 #include <pcl/point_cloud.h> 36 #include <pcl/point_types.h> 37 #include <pcl/Vertices.h> 38 #include <pcl/pcl_base.h> 90 1.0
f, 0.0
f, 0.0
f, 0.0
f,
91 0.0
f, -1.0
f, 0.0
f, 0.0
f,
92 0.0
f, 0.0
f, -1.0
f, 0.0
f);
95 1.0
f, 0.0
f, 0.0
f, 0.0
f,
96 0.0
f, 0.0
f, 1.0
f, 0.0
f,
97 0.0
f, -1.0
f, 0.0
f, 0.0
f);
100 0.0
f, 1.0
f, 0.0
f, 0.0
f,
101 -1.0
f, 0.0
f, 0.0
f, 0.0
f,
102 0.0
f, 0.0
f, 1.0
f, 0.0
f);
105 0.0
f, -1.0
f, 0.0
f, 0.0
f,
106 0.0
f, 0.0
f, 1.0
f, 0.0
f,
107 -1.0
f, 0.0
f, 0.0
f, 0.0
f);
110 0.0
f, -1.0
f, 0.0
f, 0.0
f,
111 1.0
f, 0.0
f, 0.0
f, 0.0
f,
112 0.0
f, 0.0
f, 1.0
f, 0.0
f);
115 0.0
f, -1.0
f, 0.0
f, 0.0
f,
116 0.0
f, 0.0
f, 1.0
f, 0.0
f,
117 -1.0
f, 0.0
f, 0.0
f, 0.0
f);
120 0.0
f, 0.0
f,-1.0
f, 0.0
f,
121 -1.0
f, 0.0
f, 0.0
f, 0.0
f,
122 0.0
f, 1.0
f, 0.0
f, 0.0
f);
128 mat[0][0] = transform(0,0);
129 mat[1][0] = transform(0,1);
130 mat[2][0] = transform(0,2);
131 mat[0][1] = transform(1,0);
132 mat[1][1] = transform(1,1);
133 mat[2][1] = transform(1,2);
134 mat[0][2] = transform(2,0);
135 mat[1][2] = transform(2,1);
136 mat[2][2] = transform(2,2);
138 mat[3][0] = transform(0,3);
139 mat[3][1] = transform(1,3);
140 mat[3][2] = transform(2,3);
148 transform(0,0) = mat[0][0];
149 transform(0,1) = mat[1][0];
150 transform(0,2) = mat[2][0];
151 transform(1,0) = mat[0][1];
152 transform(1,1) = mat[1][1];
153 transform(1,2) = mat[2][1];
154 transform(2,0) = mat[0][2];
155 transform(2,1) = mat[1][2];
156 transform(2,2) = mat[2][2];
158 transform(0,3) = mat[3][0];
159 transform(1,3) = mat[3][1];
160 transform(2,3) = mat[3][2];
169 cloud(new
pcl::PointCloud<
pcl::PointXYZRGB>),
170 normals(new
pcl::PointCloud<
pcl::Normal>),
171 indices(new
std::vector<int>),
174 gains[0] = gains[1] = gains[2] = 1.0f;
177 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud;
186 #if PCL_VERSION_COMPARE(>=, 1, 8, 0) 187 std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > texCoords;
213 switch (camera_rotation) {
243 int ret =
static_cast<int>(display_rotation) - color_camera_n;
262 int display_rotation,
int color_camera_rotation) {
266 r, color_camera_rotation);
static const rtabmap::Transform tango_world_T_rtabmap_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)
static void setPrintThreadId(bool printThreadId)
glm::mat4 glmFromTransform(const rtabmap::Transform &transform)
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)
rtabmap::CameraModel cameraModel
std::vector< Eigen::Vector2f > texCoords
0 degree rotation (natural orientation)
rtabmap::Transform glmToTransform(const glm::mat4 &mat)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud
ScreenRotation GetAndroidRotationFromColorCameraToDisplay(ScreenRotation display_rotation, int color_camera_rotation)
int NormalizedColorCameraRotation(int camera_rotation)
static const rtabmap::Transform rtabmap_world_T_opengl_world(0.0f, 0.0f,-1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f)
std::vector< pcl::Vertices > polygonsLowRes
static void setLevel(ULogger::Level level)
std::vector< pcl::Vertices > polygons
static const rtabmap::Transform tango_device_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)
static const rtabmap::Transform optical_T_opengl(1.0f, 0.0f, 0.0f, 0.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, -1.0f, 0.0f)
virtual std::string getClassName() const =0
const std::string & getMsg() const
pcl::PointCloud< pcl::Normal >::Ptr normals
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)
static void setEventLevel(ULogger::Level eventSentLevel)
void registerToEventsManager()
ULogger class and convenient macros.
virtual bool handleEvent(UEvent *event)
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)