RTABMapApp.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 RTABMAP_APP_H_
29 #define RTABMAP_APP_H_
30 
31 #ifdef __ANDROID__
32 #include <jni.h>
33 #endif
34 #include <memory>
35 
36 #include <tango-gl/util.h>
37 
38 #include "scene.h"
39 #include "CameraMobile.h"
40 #include "util.h"
41 #include "ProgressionStatus.h"
42 
47 #include <boost/thread/mutex.hpp>
48 #include <pcl/pcl_base.h>
49 #include <pcl/TextureMesh.h>
50 
51 
52 // RTABMapApp handles the application lifecycle and resources.
53 class RTABMapApp : public UEventsHandler {
54  public:
55  // Constructor and deconstructor.
56 #ifdef __ANDROID__
57  RTABMapApp(JNIEnv* env, jobject caller_activity);
58 #else // __APPLE__
59  RTABMapApp();
60  void setupSwiftCallbacks(void * classPtr,
61  void(*progressCallback)(void *, int, int),
62  void(*initCallback)(void *, int, const char*),
63  void(*statsUpdatedCallback)(void *,
64  int, int, int, int,
65  float,
66  int, int, int, int, int ,int,
67  float,
68  int,
69  float,
70  int,
71  float, float, float, float,
72  int, int,
73  float, float, float, float, float, float),
74  void(*cameraInfoCallback)(void *, int, const char*, const char*));
75 
76 #endif
77  ~RTABMapApp();
78 
79  void setScreenRotation(int displayRotation, int cameraRotation);
80 
81  int openDatabase(const std::string & databasePath, bool databaseInMemory, bool optimize, bool clearDatabase);
82 
83  bool isBuiltWith(int cameraDriver) const;
84 #ifdef __ANDROID__
85  bool startCamera(JNIEnv* env, jobject iBinder, jobject context, jobject activity, int driver);
86 #else // __APPLE__
87  bool startCamera();
88 #endif
89  // Allocate OpenGL resources for rendering, mainly for initializing the Scene.
90  void InitializeGLContent();
91 
92  // Setup the view port width and height.
93  void SetViewPort(int width, int height);
94 
95  // Main render loop.
96  int Render();
97 
98  void stopCamera();
99 
100  // Set render camera's viewing angle, first person, third person or top down.
101  //
102  // @param: camera_type, camera type includes first person, third person and
103  // top down
105 
106  // Touch event passed from android activity. This function only supports two
107  // touches.
108  //
109  // @param: touch_count, total count for touches.
110  // @param: event, touch event of current touch.
111  // @param: x0, normalized touch location for touch 0 on x axis.
112  // @param: y0, normalized touch location for touch 0 on y axis.
113  // @param: x1, normalized touch location for touch 1 on x axis.
114  // @param: y1, normalized touch location for touch 1 on y axis.
115  void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event,
116  float x0, float y0, float x1, float y1);
117 
118  void setPausedMapping(bool paused);
119  void setOnlineBlending(bool enabled);
120  void setMapCloudShown(bool shown);
121  void setOdomCloudShown(bool shown);
122  void setMeshRendering(bool enabled, bool withTexture);
123  void setPointSize(float value);
124  void setFOV(float angle);
125  void setOrthoCropFactor(float value);
126  void setGridRotation(float value);
127  void setLighting(bool enabled);
128  void setBackfaceCulling(bool enabled);
129  void setWireframe(bool enabled);
130  void setLocalizationMode(bool enabled);
131  void setTrajectoryMode(bool enabled);
132  void setGraphOptimization(bool enabled);
133  void setNodesFiltering(bool enabled);
134  void setGraphVisible(bool visible);
135  void setGridVisible(bool visible);
136  void setRawScanSaved(bool enabled);
137  void setCameraColor(bool enabled);
138  void setFullResolution(bool enabled);
139  void setSmoothing(bool enabled);
140  void setDepthFromMotion(bool enabled);
141  void setAppendMode(bool enabled);
143  void setDataRecorderMode(bool enabled);
144  void setMaxCloudDepth(float value);
145  void setMinCloudDepth(float value);
146  void setCloudDensityLevel(int value);
147  void setMeshAngleTolerance(float value);
148  void setMeshDecimationFactor(float value);
149  void setMeshTriangleSize(int value);
150  void setClusterRatio(float value);
151  void setMaxGainRadius(float value);
153  void setBackgroundColor(float gray);
154  void setDepthConfidence(int value);
155  void setExportPointCloudFormat(const std::string & format);
156  int setMappingParameter(const std::string & key, const std::string & value);
157  void setGPS(const rtabmap::GPS & gps);
158  void addEnvSensor(int type, float value);
159 
160  void save(const std::string & databasePath);
161  bool recover(const std::string & from, const std::string & to);
162  void cancelProcessing();
163  bool exportMesh(
164  float cloudVoxelSize,
165  bool regenerateCloud,
166  bool meshing,
167  int textureSize,
168  int textureCount,
169  int normalK,
170  bool optimized,
171  float optimizedVoxelSize,
172  int optimizedDepth,
173  int optimizedMaxPolygons,
174  float optimizedColorRadius,
175  bool optimizedCleanWhitePolygons,
176  int optimizedMinClusterSize,
177  float optimizedMaxTextureDistance,
178  int optimizedMinTextureClusterSize,
179  bool blockRendering);
180  bool postExportation(bool visualize);
181  bool writeExportedMesh(const std::string & directory, const std::string & name);
182  int postProcessing(int approach);
183 
184  void postOdometryEvent(
185  rtabmap::Transform pose,
186  float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy,
187  float depth_fx, float depth_fy, float depth_cx, float depth_cy,
188  const rtabmap::Transform & rgbFrame,
189  const rtabmap::Transform & depthFrame,
190  double stamp,
191  double depthStamp,
192  const void * yPlane, const void * uPlane, const void * vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat,
193  const void * depth, int depthLen, int depthWidth, int depthHeight, int depthFormat,
194  const void * conf, int confLen, int confWidth, int confHeight, int confFormat,
195  const float * points, int pointsLen, int pointsChannels,
196  rtabmap::Transform viewMatrix, //view matrix
197  float p00, float p11, float p02, float p12, float p22, float p32, float p23, // projection matrix
198  float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7); // tex coord
199 
200  protected:
201  virtual bool handleEvent(UEvent * event);
202 
203  private:
204  int updateMeshDecimation(int width, int height);
206  bool smoothMesh(int id, rtabmap::Mesh & mesh);
207  void gainCompensation(bool full = false);
208  std::vector<pcl::Vertices> filterOrganizedPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
209  std::vector<pcl::Vertices> filterPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
210 
211  private:
218 
244 
246 
263  std::map<std::string, float> bufferedStatsData_;
264 
267  pcl::TextureMesh::Ptr optMesh_;
268  cv::Mat optTexture_;
270  rtabmap::Transform * optRefPose_; // App crashes when loading native library if not dynamic
271 
272  // main_scene_ includes all drawable object for visualizing Tango device's
273  // movement and point cloud.
275 
277 
278  std::list<rtabmap::RtabmapEvent*> rtabmapEvents_;
279  std::list<rtabmap::SensorEvent> sensorEvents_;
280  std::list<rtabmap::Transform> poseEvents_;
281 
283 
284  boost::mutex cameraMutex_;
285  boost::mutex rtabmapMutex_;
286  boost::mutex meshesMutex_;
287  boost::mutex sensorMutex_;
288  boost::mutex poseMutex_;
289  boost::mutex renderingMutex_;
290 
292 
293  std::map<int, rtabmap::Mesh> createdMeshes_;
294  std::map<int, rtabmap::Transform> rawPoses_;
295 
296  std::pair<rtabmap::RtabmapEventInit::Status, std::string> status_;
297 
299 
300 #ifndef __ANDROID__
302  void(*swiftInitCallback)(void *, int, const char *);
304  int, int, int, int,
305  float,
306  int, int, int, int, int ,int,
307  float,
308  int,
309  float,
310  int,
311  float, float, float, float,
312  int, int,
314  void(*swiftCameraInfoEventCallback)(void *, int, const char *, const char *);
315 
316 #endif
317 };
318 
319 #endif // TANGO_POINT_CLOUD_POINT_CLOUD_APP_H_
RTABMapApp::swiftStatsUpdatedCallback
void(* swiftStatsUpdatedCallback)(void *, int, int, int, int, float, int, int, int, int, int, int, float, int, float, int, float, float, float, float, int, int, float, float, float, float, float, float)
Definition: RTABMapApp.h:303
UEventsHandler
Definition: UEventsHandler.h:128
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
int
int
RTABMapApp::meshTrianglePix_
int meshTrianglePix_
Definition: RTABMapApp.h:234
RTABMapApp::setMinCloudDepth
void setMinCloudDepth(float value)
Definition: RTABMapApp.cpp:2480
RTABMapApp::localizationMode_
bool localizationMode_
Definition: RTABMapApp.h:222
RTABMapApp::mapToOdom_
rtabmap::Transform mapToOdom_
Definition: RTABMapApp.h:282
RTABMapApp::recover
bool recover(const std::string &from, const std::string &to)
Definition: RTABMapApp.cpp:2671
RTABMapApp::getRtabmapParameters
rtabmap::ParametersMap getRtabmapParameters()
Definition: RTABMapApp.cpp:129
name
RTABMapApp::swiftInitCallback
void(* swiftInitCallback)(void *, int, const char *)
Definition: RTABMapApp.h:302
RTABMapApp::setSmoothing
void setSmoothing(bool enabled)
Definition: RTABMapApp.cpp:2431
SensorCaptureThread.h
RTABMapApp::setGridRotation
void setGridRotation(float value)
Definition: RTABMapApp.cpp:2338
RTABMapApp::graphOptimization_
bool graphOptimization_
Definition: RTABMapApp.h:220
format
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
Scene
Definition: scene.h:49
RTABMapApp::appendMode_
bool appendMode_
Definition: RTABMapApp.h:229
x1
x1
RTABMapApp::setFullResolution
void setFullResolution(bool enabled)
Definition: RTABMapApp.cpp:2423
RTABMapApp::progressionStatus_
rtabmap::ProgressionStatus progressionStatus_
Definition: RTABMapApp.h:298
RTABMapApp::totalPoints_
int totalPoints_
Definition: RTABMapApp.h:257
RTABMapApp::rawScanSaved_
bool rawScanSaved_
Definition: RTABMapApp.h:224
RTABMapApp::setAppendMode
void setAppendMode(bool enabled)
Definition: RTABMapApp.cpp:2447
CameraMobile.h
RTABMapApp::setGraphOptimization
void setGraphOptimization(bool enabled)
Definition: RTABMapApp.cpp:2369
RTABMapApp::setOnlineBlending
void setOnlineBlending(bool enabled)
Definition: RTABMapApp.cpp:2309
RTABMapApp::setScreenRotation
void setScreenRotation(int displayRotation, int cameraRotation)
Definition: RTABMapApp.cpp:360
RTABMapApp::setRawScanSaved
void setRawScanSaved(bool enabled)
Definition: RTABMapApp.cpp:2407
RTABMapApp::SetCameraType
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
Definition: RTABMapApp.cpp:2273
RTABMapApp::cameraDriver_
int cameraDriver_
Definition: RTABMapApp.h:212
RTABMapApp::gainCompensation
void gainCompensation(bool full=false)
Definition: RTABMapApp.cpp:1236
RTABMapApp::~RTABMapApp
~RTABMapApp()
Definition: RTABMapApp.cpp:336
RTABMapApp::mappingParameters_
rtabmap::ParametersMap mappingParameters_
Definition: RTABMapApp.h:245
RTABMapApp::setLocalizationMode
void setLocalizationMode(bool enabled)
Definition: RTABMapApp.cpp:2355
RTABMapApp::RTABMapApp
RTABMapApp()
Definition: RTABMapApp.cpp:216
RTABMapApp::exporting_
bool exporting_
Definition: RTABMapApp.h:250
RTABMapApp::setCameraColor
void setCameraColor(bool enabled)
Definition: RTABMapApp.cpp:2415
RTABMapApp::logHandler_
rtabmap::LogHandler * logHandler_
Definition: RTABMapApp.h:217
RTABMapApp::swiftCameraInfoEventCallback
void(* swiftCameraInfoEventCallback)(void *, int, const char *, const char *)
Definition: RTABMapApp.h:314
RTABMapApp::setWireframe
void setWireframe(bool enabled)
Definition: RTABMapApp.cpp:2350
RTABMapApp::maxCloudDepth_
float maxCloudDepth_
Definition: RTABMapApp.h:231
RTABMapApp::isBuiltWith
bool isBuiltWith(int cameraDriver) const
Definition: RTABMapApp.cpp:872
RTABMapApp::setDataRecorderMode
void setDataRecorderMode(bool enabled)
Definition: RTABMapApp.cpp:2463
RTABMapApp::sensorEvents_
std::list< rtabmap::SensorEvent > sensorEvents_
Definition: RTABMapApp.h:279
RTABMapApp::postProcessing_
bool postProcessing_
Definition: RTABMapApp.h:251
rtabmap::GPS
Definition: GPS.h:35
RTABMapApp::sensorMutex_
boost::mutex sensorMutex_
Definition: RTABMapApp.h:287
util.h
RTABMapApp::setDepthFromMotion
void setDepthFromMotion(bool enabled)
Definition: RTABMapApp.cpp:2439
type
RTABMapApp::setMeshTriangleSize
void setMeshTriangleSize(int value)
Definition: RTABMapApp.cpp:2500
RTABMapApp::SetViewPort
void SetViewPort(int width, int height)
Definition: RTABMapApp.cpp:1140
rtabmap::ProgressionStatus
Definition: ProgressionStatus.h:29
RTABMapApp::bilateralFilteringOnNextRender_
bool bilateralFilteringOnNextRender_
Definition: RTABMapApp.h:254
RTABMapApp::cancelProcessing
void cancelProcessing()
Definition: RTABMapApp.cpp:2691
RTABMapApp::setMaxCloudDepth
void setMaxCloudDepth(float value)
Definition: RTABMapApp.cpp:2475
RTABMapApp::setGraphVisible
void setGraphVisible(bool visible)
Definition: RTABMapApp.cpp:2396
RTABMapApp::trajectoryMode_
bool trajectoryMode_
Definition: RTABMapApp.h:223
RTABMapApp::stopCamera
void stopCamera()
Definition: RTABMapApp.cpp:999
RTABMapApp::postProcessing
int postProcessing(int approach)
Definition: RTABMapApp.cpp:3703
RTABMapApp::bufferedStatsData_
std::map< std::string, float > bufferedStatsData_
Definition: RTABMapApp.h:263
RTABMapApp::rtabmapEvents_
std::list< rtabmap::RtabmapEvent * > rtabmapEvents_
Definition: RTABMapApp.h:278
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
RTABMapApp
Definition: RTABMapApp.h:53
RtabmapThread.h
RTABMapApp::exportedMeshUpdated_
bool exportedMeshUpdated_
Definition: RTABMapApp.h:266
rtabmap::LogHandler
Definition: util.h:42
RTABMapApp::setRenderingTextureDecimation
void setRenderingTextureDecimation(int value)
Definition: RTABMapApp.cpp:2515
RTABMapApp::nodesFiltering_
bool nodesFiltering_
Definition: RTABMapApp.h:221
RTABMapApp::setPointSize
void setPointSize(float value)
Definition: RTABMapApp.cpp:2326
RTABMapApp::openingDatabase_
bool openingDatabase_
Definition: RTABMapApp.h:249
RTABMapApp::setGridVisible
void setGridVisible(bool visible)
Definition: RTABMapApp.cpp:2402
RTABMapApp::main_scene_
Scene main_scene_
Definition: RTABMapApp.h:274
RTABMapApp::clusterRatio_
float clusterRatio_
Definition: RTABMapApp.h:237
rtabmap::Mesh
Definition: util.h:165
RTABMapApp::rtabmap_
rtabmap::Rtabmap * rtabmap_
Definition: RTABMapApp.h:216
optimize
gtsam.ISAM2 optimize(List[GpsMeasurement] gps_measurements, List[ImuMeasurement] imu_measurements, gtsam.noiseModel.Diagonal sigma_init_x, gtsam.noiseModel.Diagonal sigma_init_v, gtsam.noiseModel.Diagonal sigma_init_b, gtsam.noiseModel.Diagonal noise_model_gps, KittiCalibration kitti_calibration, int first_gps_pose, int gps_skip)
UEvent
Definition: UEvent.h:57
RTABMapApp::renderingTextureDecimation_
int renderingTextureDecimation_
Definition: RTABMapApp.h:239
RTABMapApp::setCloudDensityLevel
void setCloudDensityLevel(int value)
Definition: RTABMapApp.cpp:2485
RTABMapApp::OnTouchEvent
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
Definition: RTABMapApp.cpp:2278
tango_gl::GestureCamera::CameraType
CameraType
Definition: gesture_camera.h:28
RTABMapApp::clearSceneOnNextRender_
bool clearSceneOnNextRender_
Definition: RTABMapApp.h:248
RTABMapApp::handleEvent
virtual bool handleEvent(UEvent *event)
Definition: RTABMapApp.cpp:4042
RTABMapApp::lastPostRenderEventTime_
double lastPostRenderEventTime_
Definition: RTABMapApp.h:261
scene.h
RTABMapApp::fullResolution_
bool fullResolution_
Definition: RTABMapApp.h:228
RTABMapApp::setMeshAngleTolerance
void setMeshAngleTolerance(float value)
Definition: RTABMapApp.cpp:2490
RTABMapApp::cloudDensityLevel_
int cloudDensityLevel_
Definition: RTABMapApp.h:233
RTABMapApp::setUpstreamRelocalizationAccThr
void setUpstreamRelocalizationAccThr(float value)
Definition: RTABMapApp.cpp:2458
RTABMapApp::poseMutex_
boost::mutex poseMutex_
Definition: RTABMapApp.h:288
RTABMapApp::updateMeshDecimation
int updateMeshDecimation(int width, int height)
Definition: RTABMapApp.cpp:803
RTABMapApp::optRefId_
int optRefId_
Definition: RTABMapApp.h:269
RTABMapApp::rtabmapThread_
rtabmap::RtabmapThread * rtabmapThread_
Definition: RTABMapApp.h:215
RTABMapApp::filterOrganizedPolygons
std::vector< pcl::Vertices > filterOrganizedPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:1020
RTABMapApp::useExternalLidar_
bool useExternalLidar_
Definition: RTABMapApp.h:230
RTABMapApp::setBackfaceCulling
void setBackfaceCulling(bool enabled)
Definition: RTABMapApp.cpp:2346
RTABMapApp::setMaxGainRadius
void setMaxGainRadius(float value)
Definition: RTABMapApp.cpp:2510
x0
x0
tango_gl::GestureCamera::TouchEvent
TouchEvent
Definition: gesture_camera.h:36
RTABMapApp::maxGainRadius_
float maxGainRadius_
Definition: RTABMapApp.h:238
RTABMapApp::save
void save(const std::string &databasePath)
Definition: RTABMapApp.cpp:2616
RTABMapApp::createdMeshes_
std::map< int, rtabmap::Mesh > createdMeshes_
Definition: RTABMapApp.h:293
RTABMapApp::setMeshDecimationFactor
void setMeshDecimationFactor(float value)
Definition: RTABMapApp.cpp:2495
RTABMapApp::sensorCaptureThread_
rtabmap::SensorCaptureThread * sensorCaptureThread_
Definition: RTABMapApp.h:214
RTABMapApp::visualizingMesh_
bool visualizingMesh_
Definition: RTABMapApp.h:265
SensorEvent.h
RTABMapApp::optMesh_
pcl::TextureMesh::Ptr optMesh_
Definition: RTABMapApp.h:267
RTABMapApp::upstreamRelocalizationMaxAcc_
float upstreamRelocalizationMaxAcc_
Definition: RTABMapApp.h:242
RTABMapApp::cameraColor_
bool cameraColor_
Definition: RTABMapApp.h:227
glm::angle
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
RTABMapApp::writeExportedMesh
bool writeExportedMesh(const std::string &directory, const std::string &name)
Definition: RTABMapApp.cpp:3568
RTABMapApp::setLighting
void setLighting(bool enabled)
Definition: RTABMapApp.cpp:2342
RTABMapApp::cameraJustInitialized_
bool cameraJustInitialized_
Definition: RTABMapApp.h:256
RTABMapApp::setDepthConfidence
void setDepthConfidence(int value)
Definition: RTABMapApp.cpp:2529
RTABMapApp::odomCloudShown_
bool odomCloudShown_
Definition: RTABMapApp.h:219
RTABMapApp::setBackgroundColor
void setBackgroundColor(float gray)
Definition: RTABMapApp.cpp:2521
key
const gtsam::Symbol key( 'X', 0)
RTABMapApp::smoothing_
bool smoothing_
Definition: RTABMapApp.h:225
RTABMapApp::exportPointCloudFormat_
std::string exportPointCloudFormat_
Definition: RTABMapApp.h:243
y1
CEPHES_EXTERN_EXPORT double y1(double x)
RTABMapApp::setMappingParameter
int setMappingParameter(const std::string &key, const std::string &value)
Definition: RTABMapApp.cpp:2554
RTABMapApp::setOrthoCropFactor
void setOrthoCropFactor(float value)
Definition: RTABMapApp.cpp:2334
RTABMapApp::setupSwiftCallbacks
void setupSwiftCallbacks(void *classPtr, void(*progressCallback)(void *, int, int), void(*initCallback)(void *, int, const char *), void(*statsUpdatedCallback)(void *, int, int, int, int, float, int, int, int, int, int, int, float, int, float, int, float, float, float, float, int, int, float, float, float, float, float, float), void(*cameraInfoCallback)(void *, int, const char *, const char *))
Definition: RTABMapApp.cpp:312
RTABMapApp::filterPolygonsOnNextRender_
bool filterPolygonsOnNextRender_
Definition: RTABMapApp.h:252
RTABMapApp::setClusterRatio
void setClusterRatio(float value)
Definition: RTABMapApp.cpp:2505
RTABMapApp::takeScreenshotOnNextRender_
bool takeScreenshotOnNextRender_
Definition: RTABMapApp.h:255
RTABMapApp::renderingMutex_
boost::mutex renderingMutex_
Definition: RTABMapApp.h:289
rtabmap::Transform
Definition: Transform.h:41
RTABMapApp::rtabmapMutex_
boost::mutex rtabmapMutex_
Definition: RTABMapApp.h:285
full
@ full
Definition: lz4.c:365
RTABMapApp::filterPolygons
std::vector< pcl::Vertices > filterPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:1087
RTABMapApp::setMapCloudShown
void setMapCloudShown(bool shown)
Definition: RTABMapApp.cpp:2313
y0
CEPHES_EXTERN_EXPORT double y0(double x)
RTABMapApp::renderingTime_
float renderingTime_
Definition: RTABMapApp.h:260
UEventsHandler.h
RTABMapApp::postExportation
bool postExportation(bool visualize)
Definition: RTABMapApp.cpp:3492
RTABMapApp::openDatabase
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
Definition: RTABMapApp.cpp:373
RTABMapApp::minCloudDepth_
float minCloudDepth_
Definition: RTABMapApp.h:232
env
RTABMapApp::setExportPointCloudFormat
void setExportPointCloudFormat(const std::string &format)
Definition: RTABMapApp.cpp:2538
USemaphore
Definition: USemaphore.h:54
RTABMapApp::depthFromMotion_
bool depthFromMotion_
Definition: RTABMapApp.h:226
RTABMapApp::gainCompensationOnNextRender_
int gainCompensationOnNextRender_
Definition: RTABMapApp.h:253
RTABMapApp::backgroundColor_
float backgroundColor_
Definition: RTABMapApp.h:240
RTABMapApp::screenshotReady_
USemaphore screenshotReady_
Definition: RTABMapApp.h:291
RTABMapApp::fpsTime_
UTimer fpsTime_
Definition: RTABMapApp.h:276
rtabmap::CameraMobile
Definition: CameraMobile.h:71
RTABMapApp::setFOV
void setFOV(float angle)
Definition: RTABMapApp.cpp:2330
RTABMapApp::postOdometryEvent
void postOdometryEvent(rtabmap::Transform pose, float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy, float depth_fx, float depth_fy, float depth_cx, float depth_cy, const rtabmap::Transform &rgbFrame, const rtabmap::Transform &depthFrame, double stamp, double depthStamp, const void *yPlane, const void *uPlane, const void *vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, const void *depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, const void *conf, int confLen, int confWidth, int confHeight, int confFormat, const float *points, int pointsLen, int pointsChannels, rtabmap::Transform viewMatrix, float p00, float p11, float p02, float p12, float p22, float p32, float p23, float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7)
Definition: RTABMapApp.cpp:3802
RTABMapApp::setGPS
void setGPS(const rtabmap::GPS &gps)
Definition: RTABMapApp.cpp:2598
RTABMapApp::status_
std::pair< rtabmap::RtabmapEventInit::Status, std::string > status_
Definition: RTABMapApp.h:296
UTimer
Definition: UTimer.h:46
RTABMapApp::smoothMesh
bool smoothMesh(int id, rtabmap::Mesh &mesh)
Definition: RTABMapApp.cpp:1171
float
float
RTABMapApp::totalPolygons_
int totalPolygons_
Definition: RTABMapApp.h:258
p22
p22
RTABMapApp::setPausedMapping
void setPausedMapping(bool paused)
Definition: RTABMapApp.cpp:2284
RTABMapApp::optTexture_
cv::Mat optTexture_
Definition: RTABMapApp.h:268
rtabmap::Rtabmap
Definition: Rtabmap.h:54
RTABMapApp::dataRecorderMode_
bool dataRecorderMode_
Definition: RTABMapApp.h:247
RTABMapApp::meshAngleToleranceDeg_
float meshAngleToleranceDeg_
Definition: RTABMapApp.h:235
ProgressionStatus.h
RTABMapApp::Render
int Render()
Definition: RTABMapApp.cpp:1292
RTABMapApp::optRefPose_
rtabmap::Transform * optRefPose_
Definition: RTABMapApp.h:270
RTABMapApp::exportMesh
bool exportMesh(float cloudVoxelSize, bool regenerateCloud, bool meshing, int textureSize, int textureCount, int normalK, bool optimized, float optimizedVoxelSize, int optimizedDepth, int optimizedMaxPolygons, float optimizedColorRadius, bool optimizedCleanWhitePolygons, int optimizedMinClusterSize, float optimizedMaxTextureDistance, int optimizedMinTextureClusterSize, bool blockRendering)
Definition: RTABMapApp.cpp:2697
RTABMapApp::rawPoses_
std::map< int, rtabmap::Transform > rawPoses_
Definition: RTABMapApp.h:294
RTABMapApp::meshDecimationFactor_
float meshDecimationFactor_
Definition: RTABMapApp.h:236
RTABMapApp::depthConfidence_
int depthConfidence_
Definition: RTABMapApp.h:241
RTABMapApp::startCamera
bool startCamera()
Definition: RTABMapApp.cpp:906
RTABMapApp::poseEvents_
std::list< rtabmap::Transform > poseEvents_
Definition: RTABMapApp.h:280
RTABMapApp::InitializeGLContent
void InitializeGLContent()
Definition: RTABMapApp.cpp:1130
RTABMapApp::setMeshRendering
void setMeshRendering(bool enabled, bool withTexture)
Definition: RTABMapApp.cpp:2322
value
value
RTABMapApp::setNodesFiltering
void setNodesFiltering(bool enabled)
Definition: RTABMapApp.cpp:2391
RTABMapApp::camera_
rtabmap::CameraMobile * camera_
Definition: RTABMapApp.h:213
conf
RTABMapApp::setOdomCloudShown
void setOdomCloudShown(bool shown)
Definition: RTABMapApp.cpp:2317
RTABMapApp::lastDrawnCloudsCount_
int lastDrawnCloudsCount_
Definition: RTABMapApp.h:259
RTABMapApp::lastPoseEventTime_
double lastPoseEventTime_
Definition: RTABMapApp.h:262
RTABMapApp::addEnvSensor
void addEnvSensor(int type, float value)
Definition: RTABMapApp.cpp:2607
RTABMapApp::meshesMutex_
boost::mutex meshesMutex_
Definition: RTABMapApp.h:286
rtabmap::RtabmapThread
Definition: RtabmapThread.h:51
RTABMapApp::cameraMutex_
boost::mutex cameraMutex_
Definition: RTABMapApp.h:284
RTABMapApp::swiftClassPtr_
void * swiftClassPtr_
Definition: RTABMapApp.h:301
RTABMapApp::setTrajectoryMode
void setTrajectoryMode(bool enabled)
Definition: RTABMapApp.cpp:2363


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:51