Go to the documentation of this file.
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.0f, 0.0f, 0.0f, 0.0f,
91 0.0f, -1.0f, 0.0f, 0.0f,
92 0.0f, 0.0f, -1.0f, 0.0f);
95 1.0f, 0.0f, 0.0f, 0.0f,
96 0.0f, 0.0f, 1.0f, 0.0f,
97 0.0f, -1.0f, 0.0f, 0.0f);
100 0.0f, 1.0f, 0.0f, 0.0f,
101 -1.0f, 0.0f, 0.0f, 0.0f,
102 0.0f, 0.0f, 1.0f, 0.0f);
105 0.0f, -1.0f, 0.0f, 0.0f,
106 0.0f, 0.0f, 1.0f, 0.0f,
107 -1.0f, 0.0f, 0.0f, 0.0f);
110 0.0f, -1.0f, 0.0f, 0.0f,
111 1.0f, 0.0f, 0.0f, 0.0f,
112 0.0f, 0.0f, 1.0f, 0.0f);
115 0.0f, -1.0f, 0.0f, 0.0f,
116 0.0f, 0.0f, 1.0f, 0.0f,
117 -1.0f, 0.0f, 0.0f, 0.0f);
120 0.0f, 0.0f,-1.0f, 0.0f,
121 -1.0f, 0.0f, 0.0f, 0.0f,
122 0.0f, 1.0f, 0.0f, 0.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);
int NormalizedColorCameraRotation(int camera_rotation)
ScreenRotation GetAndroidRotationFromColorCameraToDisplay(ScreenRotation display_rotation, int color_camera_rotation)
void registerToEventsManager()
std::vector< pcl::Vertices > polygonsLowRes
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 setLevel(ULogger::Level level)
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)
pcl::PointCloud< pcl::Normal >::Ptr normals
@ ROTATION_IGNORED
Not apply any rotation.
virtual bool handleEvent(UEvent *event)
@ ROTATION_270
270 degree rotation.
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)
rtabmap::CameraModel cameraModel
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)
static void setEventLevel(ULogger::Level eventSentLevel)
virtual std::string getClassName() const =0
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 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)
@ ROTATION_90
90 degree rotation.
@ ROTATION_180
180 degree rotation.
std::vector< pcl::Vertices > polygons
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
ULogger class and convenient macros.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud
EIGEN_DONT_INLINE void transform(const Quaternion< Scalar > &t, Data &data)
static void setPrintThreadId(bool printThreadId)
@ ROTATION_0
0 degree rotation (natural orientation)
glm::mat4 glmFromTransform(const rtabmap::Transform &transform)
rtabmap::Transform glmToTransform(const glm::mat4 &mat)
std::vector< Eigen::Vector2f > texCoords
const std::string & getMsg() const
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)
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:23