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 #include "Measure.h"
52 
53 // RTABMapApp handles the application lifecycle and resources.
54 class RTABMapApp : public UEventsHandler {
55  public:
56  // Constructor and deconstructor.
57 #ifdef __ANDROID__
58  RTABMapApp(JNIEnv* env, jobject caller_activity);
59 #else // __APPLE__
60  RTABMapApp();
61  void setupSwiftCallbacks(void * classPtr,
62  void(*progressCallback)(void *, int, int),
63  void(*initCallback)(void *, int, const char*),
64  void(*statsUpdatedCallback)(void *,
65  int, int, int, int,
66  float,
67  int, int, int, int, int ,int,
68  float,
69  int,
70  float,
71  int,
72  float, float, float, float,
73  int, int,
74  float, float, float, float, float, float),
75  void(*cameraInfoCallback)(void *, int, const char*, const char*));
76 
77 #endif
78  ~RTABMapApp();
79 
80  void setScreenRotation(int displayRotation, int cameraRotation);
81 
82  int openDatabase(const std::string & databasePath, bool databaseInMemory, bool optimize, bool clearDatabase);
83 
84  bool isBuiltWith(int cameraDriver) const;
85 #ifdef __ANDROID__
86  bool startCamera(JNIEnv* env, jobject iBinder, jobject context, jobject activity, int driver);
87 #else // __APPLE__
88  bool startCamera();
89 #endif
90  // Allocate OpenGL resources for rendering, mainly for initializing the Scene.
91  void InitializeGLContent();
92 
93  // Setup the view port width and height.
94  void SetViewPort(int width, int height);
95 
96  // Main render loop.
97  int Render();
98 
99  void stopCamera();
100 
101  // Set render camera's viewing angle, first person, third person or top down.
102  //
103  // @param: camera_type, camera type includes first person, third person and
104  // top down
106 
107  // Touch event passed from android activity. This function only supports two
108  // touches.
109  //
110  // @param: touch_count, total count for touches.
111  // @param: event, touch event of current touch.
112  // @param: x0, normalized touch location for touch 0 on x axis.
113  // @param: y0, normalized touch location for touch 0 on y axis.
114  // @param: x1, normalized touch location for touch 1 on x axis.
115  // @param: y1, normalized touch location for touch 1 on y axis.
116  void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event,
117  float x0, float y0, float x1, float y1);
118 
119  void setPausedMapping(bool paused);
120  void setOnlineBlending(bool enabled);
121  void setMapCloudShown(bool shown);
122  void setOdomCloudShown(bool shown);
123  void setMeshRendering(bool enabled, bool withTexture);
124  void setPointSize(float value);
125  void setFOV(float angle);
126  void setOrthoCropFactor(float value);
127  void setGridRotation(float value);
128  void setLighting(bool enabled);
129  void setBackfaceCulling(bool enabled);
130  void setWireframe(bool enabled);
131  void setTextureColorSeamsHidden(bool hidden);
132  void setLocalizationMode(bool enabled);
133  void setTrajectoryMode(bool enabled);
134  void setGraphOptimization(bool enabled);
135  void setNodesFiltering(bool enabled);
136  void setGraphVisible(bool visible);
137  void setGridVisible(bool visible);
138  void setRawScanSaved(bool enabled);
139  void setCameraColor(bool enabled);
140  void setFullResolution(bool enabled);
141  void setSmoothing(bool enabled);
142  void setDepthFromMotion(bool enabled);
143  void setAppendMode(bool enabled);
145  void setDataRecorderMode(bool enabled);
146  void setMaxCloudDepth(float value);
147  void setMinCloudDepth(float value);
148  void setCloudDensityLevel(int value);
149  void setMeshAngleTolerance(float value);
150  void setMeshDecimationFactor(float value);
151  void setMeshTriangleSize(int value);
152  void setClusterRatio(float value);
153  void setMaxGainRadius(float value);
155  void setBackgroundColor(float gray);
156  void setDepthConfidence(int value);
157  void setExportPointCloudFormat(const std::string & format);
158  int setMappingParameter(const std::string & key, const std::string & value);
159  void setGPS(const rtabmap::GPS & gps);
160  void addEnvSensor(int type, float value);
161 
162  void save(const std::string & databasePath);
163  bool recover(const std::string & from, const std::string & to);
164  void cancelProcessing();
165  bool exportMesh(
166  float cloudVoxelSize,
167  bool regenerateCloud,
168  bool meshing,
169  int textureSize,
170  int textureCount,
171  int normalK,
172  bool optimized,
173  float optimizedVoxelSize,
174  int optimizedDepth,
175  int optimizedMaxPolygons,
176  float optimizedColorRadius,
177  bool optimizedCleanWhitePolygons,
178  int optimizedMinClusterSize,
179  float optimizedMaxTextureDistance,
180  int optimizedMinTextureClusterSize,
181  int textureVertexColorPolicy,
182  bool blockRendering);
183  bool postExportation(bool visualize);
184  bool writeExportedMesh(const std::string & directory, const std::string & name);
185  int postProcessing(int approach);
186  void clearMeasures();
187  void showMeasures(bool x, bool y, bool z, bool custom);
188  void setMeasuringMode(int mode);
190  void teleportButtonClicked();
191  void removeMeasure();
192  void setMetricSystem(bool enabled);
193  void setMeasuringTextSize(float size);
194 
195  void postOdometryEvent(
196  rtabmap::Transform pose,
197  float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy,
198  float depth_fx, float depth_fy, float depth_cx, float depth_cy,
199  const rtabmap::Transform & rgbFrame,
200  const rtabmap::Transform & depthFrame,
201  double stamp,
202  double depthStamp,
203  const void * yPlane, const void * uPlane, const void * vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat,
204  const void * depth, int depthLen, int depthWidth, int depthHeight, int depthFormat,
205  const void * conf, int confLen, int confWidth, int confHeight, int confFormat,
206  const float * points, int pointsLen, int pointsChannels,
207  rtabmap::Transform viewMatrix, //view matrix
208  float p00, float p11, float p02, float p12, float p22, float p32, float p23, // projection matrix
209  float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7); // tex coord
210 
211  protected:
212  virtual bool handleEvent(UEvent * event);
213 
214  private:
215  int updateMeshDecimation(int width, int height);
217  void updateMeasuringState();
218  bool smoothMesh(int id, rtabmap::Mesh & mesh);
219  void gainCompensation(bool full = false);
220  std::vector<pcl::Vertices> filterOrganizedPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
221  std::vector<pcl::Vertices> filterPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
222 
223  private:
230 
256 
258 
275  std::map<std::string, float> bufferedStatsData_;
276 
279  pcl::TextureMesh::Ptr optTextureMesh_;
280  cv::Mat optTexture_;
283  rtabmap::Transform * optRefPose_; // App crashes when loading native library if not dynamic
284  std::list<Measure> measures_; // In opengl frame
289  std::vector<cv::Vec3f> snapAxes_;
294  std::vector<cv::Point3f> measuringTmpPts_; // In opengl frame
295  std::vector<cv::Point3f> measuringTmpNormals_; // In opengl frame
296  pcl::PointCloud<pcl::PointXYZRGB>::Ptr targetPoint_;
297  pcl::PointCloud<pcl::PointXYZ>::Ptr quadSample_;
298  std::vector<pcl::Vertices> quadSamplePolygons_;
299  // main_scene_ includes all drawable object for visualizing Tango device's
300  // movement and point cloud.
302 
304 
305  std::list<rtabmap::RtabmapEvent*> rtabmapEvents_;
306  std::list<rtabmap::SensorEvent> sensorEvents_;
307  std::list<rtabmap::Transform> poseEvents_;
308 
310 
311  boost::mutex cameraMutex_;
312  boost::mutex rtabmapMutex_;
313  boost::mutex meshesMutex_;
314  boost::mutex sensorMutex_;
315  boost::mutex poseMutex_;
316  boost::mutex renderingMutex_;
317 
319 
320  std::map<int, rtabmap::Mesh> createdMeshes_;
321  std::map<int, rtabmap::Transform> rawPoses_;
322 
323  std::pair<rtabmap::RtabmapEventInit::Status, std::string> status_;
324 
326 
327 #ifndef __ANDROID__
329  void(*swiftInitCallback)(void *, int, const char *);
331  int, int, int, int,
332  float,
333  int, int, int, int, int ,int,
334  float,
335  int,
336  float,
337  int,
338  float, float, float, float,
339  int, int,
341  void(*swiftCameraInfoEventCallback)(void *, int, const char *, const char *);
342 
343 #endif
344 };
345 
346 #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:330
UEventsHandler
Definition: UEventsHandler.h:128
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
RTABMapApp::teleportButtonClicked
void teleportButtonClicked()
Definition: RTABMapApp.cpp:4429
int
int
RTABMapApp::measuringMode_
int measuringMode_
Definition: RTABMapApp.h:290
RTABMapApp::meshTrianglePix_
int meshTrianglePix_
Definition: RTABMapApp.h:246
RTABMapApp::measuringTmpPts_
std::vector< cv::Point3f > measuringTmpPts_
Definition: RTABMapApp.h:294
RTABMapApp::setMinCloudDepth
void setMinCloudDepth(float value)
Definition: RTABMapApp.cpp:3059
RTABMapApp::localizationMode_
bool localizationMode_
Definition: RTABMapApp.h:234
RTABMapApp::mapToOdom_
rtabmap::Transform mapToOdom_
Definition: RTABMapApp.h:309
RTABMapApp::recover
bool recover(const std::string &from, const std::string &to)
Definition: RTABMapApp.cpp:3250
RTABMapApp::getRtabmapParameters
rtabmap::ParametersMap getRtabmapParameters()
Definition: RTABMapApp.cpp:129
name
RTABMapApp::swiftInitCallback
void(* swiftInitCallback)(void *, int, const char *)
Definition: RTABMapApp.h:329
RTABMapApp::setSmoothing
void setSmoothing(bool enabled)
Definition: RTABMapApp.cpp:3010
SensorCaptureThread.h
RTABMapApp::setGridRotation
void setGridRotation(float value)
Definition: RTABMapApp.cpp:2904
RTABMapApp::graphOptimization_
bool graphOptimization_
Definition: RTABMapApp.h:232
format
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
Scene
Definition: scene.h:52
x1
Double_ x1(x1_key)
RTABMapApp::appendMode_
bool appendMode_
Definition: RTABMapApp.h:241
RTABMapApp::setFullResolution
void setFullResolution(bool enabled)
Definition: RTABMapApp.cpp:3002
RTABMapApp::progressionStatus_
rtabmap::ProgressionStatus progressionStatus_
Definition: RTABMapApp.h:325
RTABMapApp::totalPoints_
int totalPoints_
Definition: RTABMapApp.h:269
RTABMapApp::rawScanSaved_
bool rawScanSaved_
Definition: RTABMapApp.h:236
RTABMapApp::setAppendMode
void setAppendMode(bool enabled)
Definition: RTABMapApp.cpp:3026
CameraMobile.h
RTABMapApp::setGraphOptimization
void setGraphOptimization(bool enabled)
Definition: RTABMapApp.cpp:2948
RTABMapApp::setOnlineBlending
void setOnlineBlending(bool enabled)
Definition: RTABMapApp.cpp:2875
RTABMapApp::setScreenRotation
void setScreenRotation(int displayRotation, int cameraRotation)
Definition: RTABMapApp.cpp:379
RTABMapApp::setRawScanSaved
void setRawScanSaved(bool enabled)
Definition: RTABMapApp.cpp:2986
RTABMapApp::SetCameraType
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
Definition: RTABMapApp.cpp:2839
RTABMapApp::cameraDriver_
int cameraDriver_
Definition: RTABMapApp.h:224
RTABMapApp::gainCompensation
void gainCompensation(bool full=false)
Definition: RTABMapApp.cpp:1260
RTABMapApp::~RTABMapApp
~RTABMapApp()
Definition: RTABMapApp.cpp:355
RTABMapApp::mappingParameters_
rtabmap::ParametersMap mappingParameters_
Definition: RTABMapApp.h:257
size
Index size
RTABMapApp::setLocalizationMode
void setLocalizationMode(bool enabled)
Definition: RTABMapApp.cpp:2934
RTABMapApp::RTABMapApp
RTABMapApp()
Definition: RTABMapApp.cpp:218
RTABMapApp::exporting_
bool exporting_
Definition: RTABMapApp.h:262
RTABMapApp::setCameraColor
void setCameraColor(bool enabled)
Definition: RTABMapApp.cpp:2994
RTABMapApp::logHandler_
rtabmap::LogHandler * logHandler_
Definition: RTABMapApp.h:229
RTABMapApp::swiftCameraInfoEventCallback
void(* swiftCameraInfoEventCallback)(void *, int, const char *, const char *)
Definition: RTABMapApp.h:341
RTABMapApp::setWireframe
void setWireframe(bool enabled)
Definition: RTABMapApp.cpp:2925
RTABMapApp::updateMeasuringState
void updateMeasuringState()
Definition: RTABMapApp.cpp:2450
RTABMapApp::maxCloudDepth_
float maxCloudDepth_
Definition: RTABMapApp.h:243
RTABMapApp::isBuiltWith
bool isBuiltWith(int cameraDriver) const
Definition: RTABMapApp.cpp:896
RTABMapApp::optTextureMesh_
pcl::TextureMesh::Ptr optTextureMesh_
Definition: RTABMapApp.h:279
RTABMapApp::setDataRecorderMode
void setDataRecorderMode(bool enabled)
Definition: RTABMapApp.cpp:3042
RTABMapApp::sensorEvents_
std::list< rtabmap::SensorEvent > sensorEvents_
Definition: RTABMapApp.h:306
RTABMapApp::postProcessing_
bool postProcessing_
Definition: RTABMapApp.h:263
rtabmap::GPS
Definition: GPS.h:35
RTABMapApp::sensorMutex_
boost::mutex sensorMutex_
Definition: RTABMapApp.h:314
util.h
RTABMapApp::setDepthFromMotion
void setDepthFromMotion(bool enabled)
Definition: RTABMapApp.cpp:3018
type
RTABMapApp::setMeshTriangleSize
void setMeshTriangleSize(int value)
Definition: RTABMapApp.cpp:3079
RTABMapApp::SetViewPort
void SetViewPort(int width, int height)
Definition: RTABMapApp.cpp:1164
rtabmap::ProgressionStatus
Definition: ProgressionStatus.h:29
Measure.h
y
Matrix3f y
RTABMapApp::bilateralFilteringOnNextRender_
bool bilateralFilteringOnNextRender_
Definition: RTABMapApp.h:266
RTABMapApp::setMetricSystem
void setMetricSystem(bool enabled)
Definition: RTABMapApp.cpp:4447
RTABMapApp::cancelProcessing
void cancelProcessing()
Definition: RTABMapApp.cpp:3270
RTABMapApp::setTextureColorSeamsHidden
void setTextureColorSeamsHidden(bool hidden)
Definition: RTABMapApp.cpp:2929
RTABMapApp::setMaxCloudDepth
void setMaxCloudDepth(float value)
Definition: RTABMapApp.cpp:3054
RTABMapApp::setMeasuringTextSize
void setMeasuringTextSize(float size)
Definition: RTABMapApp.cpp:4456
RTABMapApp::setGraphVisible
void setGraphVisible(bool visible)
Definition: RTABMapApp.cpp:2975
RTABMapApp::trajectoryMode_
bool trajectoryMode_
Definition: RTABMapApp.h:235
RTABMapApp::stopCamera
void stopCamera()
Definition: RTABMapApp.cpp:1023
RTABMapApp::postProcessing
int postProcessing(int approach)
Definition: RTABMapApp.cpp:4306
RTABMapApp::bufferedStatsData_
std::map< std::string, float > bufferedStatsData_
Definition: RTABMapApp.h:275
RTABMapApp::rtabmapEvents_
std::list< rtabmap::RtabmapEvent * > rtabmapEvents_
Definition: RTABMapApp.h:305
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
RTABMapApp
Definition: RTABMapApp.h:54
RTABMapApp::quadSample_
pcl::PointCloud< pcl::PointXYZ >::Ptr quadSample_
Definition: RTABMapApp.h:297
RtabmapThread.h
RTABMapApp::exportedMeshUpdated_
bool exportedMeshUpdated_
Definition: RTABMapApp.h:278
rtabmap::LogHandler
Definition: util.h:42
RTABMapApp::setRenderingTextureDecimation
void setRenderingTextureDecimation(int value)
Definition: RTABMapApp.cpp:3094
RTABMapApp::nodesFiltering_
bool nodesFiltering_
Definition: RTABMapApp.h:233
RTABMapApp::setPointSize
void setPointSize(float value)
Definition: RTABMapApp.cpp:2892
RTABMapApp::openingDatabase_
bool openingDatabase_
Definition: RTABMapApp.h:261
RTABMapApp::setGridVisible
void setGridVisible(bool visible)
Definition: RTABMapApp.cpp:2981
RTABMapApp::main_scene_
Scene main_scene_
Definition: RTABMapApp.h:301
RTABMapApp::clusterRatio_
float clusterRatio_
Definition: RTABMapApp.h:249
rtabmap::Mesh
Definition: util.h:165
RTABMapApp::rtabmap_
rtabmap::Rtabmap * rtabmap_
Definition: RTABMapApp.h:228
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:251
RTABMapApp::setCloudDensityLevel
void setCloudDensityLevel(int value)
Definition: RTABMapApp.cpp:3064
RTABMapApp::OnTouchEvent
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
Definition: RTABMapApp.cpp:2844
tango_gl::GestureCamera::CameraType
CameraType
Definition: gesture_camera.h:28
RTABMapApp::clearSceneOnNextRender_
bool clearSceneOnNextRender_
Definition: RTABMapApp.h:260
RTABMapApp::snapAxes_
std::vector< cv::Vec3f > snapAxes_
Definition: RTABMapApp.h:289
RTABMapApp::handleEvent
virtual bool handleEvent(UEvent *event)
Definition: RTABMapApp.cpp:4705
mode
const DiscreteKey mode
RTABMapApp::quadSamplePolygons_
std::vector< pcl::Vertices > quadSamplePolygons_
Definition: RTABMapApp.h:298
RTABMapApp::lastPostRenderEventTime_
double lastPostRenderEventTime_
Definition: RTABMapApp.h:273
scene.h
RTABMapApp::fullResolution_
bool fullResolution_
Definition: RTABMapApp.h:240
RTABMapApp::addMeasureButtonClicked
void addMeasureButtonClicked()
Definition: RTABMapApp.cpp:4420
RTABMapApp::setMeshAngleTolerance
void setMeshAngleTolerance(float value)
Definition: RTABMapApp.cpp:3069
RTABMapApp::cloudDensityLevel_
int cloudDensityLevel_
Definition: RTABMapApp.h:245
RTABMapApp::setUpstreamRelocalizationAccThr
void setUpstreamRelocalizationAccThr(float value)
Definition: RTABMapApp.cpp:3037
RTABMapApp::poseMutex_
boost::mutex poseMutex_
Definition: RTABMapApp.h:315
RTABMapApp::removeMeasureClicked_
bool removeMeasureClicked_
Definition: RTABMapApp.h:293
RTABMapApp::removeMeasure
void removeMeasure()
Definition: RTABMapApp.cpp:4438
RTABMapApp::updateMeshDecimation
int updateMeshDecimation(int width, int height)
Definition: RTABMapApp.cpp:827
RTABMapApp::optRefId_
int optRefId_
Definition: RTABMapApp.h:282
RTABMapApp::rtabmapThread_
rtabmap::RtabmapThread * rtabmapThread_
Definition: RTABMapApp.h:227
RTABMapApp::filterOrganizedPolygons
std::vector< pcl::Vertices > filterOrganizedPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:1044
RTABMapApp::useExternalLidar_
bool useExternalLidar_
Definition: RTABMapApp.h:242
RTABMapApp::setBackfaceCulling
void setBackfaceCulling(bool enabled)
Definition: RTABMapApp.cpp:2921
RTABMapApp::setMaxGainRadius
void setMaxGainRadius(float value)
Definition: RTABMapApp.cpp:3089
x0
x0
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, int textureVertexColorPolicy, bool blockRendering)
Definition: RTABMapApp.cpp:3276
tango_gl::GestureCamera::TouchEvent
TouchEvent
Definition: gesture_camera.h:36
RTABMapApp::maxGainRadius_
float maxGainRadius_
Definition: RTABMapApp.h:250
RTABMapApp::save
void save(const std::string &databasePath)
Definition: RTABMapApp.cpp:3195
RTABMapApp::createdMeshes_
std::map< int, rtabmap::Mesh > createdMeshes_
Definition: RTABMapApp.h:320
RTABMapApp::setMeshDecimationFactor
void setMeshDecimationFactor(float value)
Definition: RTABMapApp.cpp:3074
RTABMapApp::sensorCaptureThread_
rtabmap::SensorCaptureThread * sensorCaptureThread_
Definition: RTABMapApp.h:226
RTABMapApp::visualizingMesh_
bool visualizingMesh_
Definition: RTABMapApp.h:277
SensorEvent.h
RTABMapApp::teleportClicked_
bool teleportClicked_
Definition: RTABMapApp.h:292
z
z
RTABMapApp::snapAxisThr_
float snapAxisThr_
Definition: RTABMapApp.h:288
x
x
RTABMapApp::upstreamRelocalizationMaxAcc_
float upstreamRelocalizationMaxAcc_
Definition: RTABMapApp.h:254
RTABMapApp::cameraColor_
bool cameraColor_
Definition: RTABMapApp.h:239
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:4171
RTABMapApp::setLighting
void setLighting(bool enabled)
Definition: RTABMapApp.cpp:2917
RTABMapApp::targetPoint_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr targetPoint_
Definition: RTABMapApp.h:296
RTABMapApp::cameraJustInitialized_
bool cameraJustInitialized_
Definition: RTABMapApp.h:268
RTABMapApp::setDepthConfidence
void setDepthConfidence(int value)
Definition: RTABMapApp.cpp:3108
RTABMapApp::odomCloudShown_
bool odomCloudShown_
Definition: RTABMapApp.h:231
RTABMapApp::setBackgroundColor
void setBackgroundColor(float gray)
Definition: RTABMapApp.cpp:3100
key
const gtsam::Symbol key( 'X', 0)
RTABMapApp::smoothing_
bool smoothing_
Definition: RTABMapApp.h:237
RTABMapApp::exportPointCloudFormat_
std::string exportPointCloudFormat_
Definition: RTABMapApp.h:255
y1
CEPHES_EXTERN_EXPORT double y1(double x)
RTABMapApp::setMappingParameter
int setMappingParameter(const std::string &key, const std::string &value)
Definition: RTABMapApp.cpp:3133
RTABMapApp::setOrthoCropFactor
void setOrthoCropFactor(float value)
Definition: RTABMapApp.cpp:2900
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:331
RTABMapApp::filterPolygonsOnNextRender_
bool filterPolygonsOnNextRender_
Definition: RTABMapApp.h:264
RTABMapApp::setClusterRatio
void setClusterRatio(float value)
Definition: RTABMapApp.cpp:3084
RTABMapApp::takeScreenshotOnNextRender_
bool takeScreenshotOnNextRender_
Definition: RTABMapApp.h:267
RTABMapApp::renderingMutex_
boost::mutex renderingMutex_
Definition: RTABMapApp.h:316
rtabmap::Transform
Definition: Transform.h:41
RTABMapApp::rtabmapMutex_
boost::mutex rtabmapMutex_
Definition: RTABMapApp.h:312
RTABMapApp::measuresUpdated_
bool measuresUpdated_
Definition: RTABMapApp.h:285
full
@ full
Definition: lz4.c:365
RTABMapApp::measuringTmpNormals_
std::vector< cv::Point3f > measuringTmpNormals_
Definition: RTABMapApp.h:295
RTABMapApp::filterPolygons
std::vector< pcl::Vertices > filterPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:1111
RTABMapApp::setMapCloudShown
void setMapCloudShown(bool shown)
Definition: RTABMapApp.cpp:2879
y0
CEPHES_EXTERN_EXPORT double y0(double x)
RTABMapApp::renderingTime_
float renderingTime_
Definition: RTABMapApp.h:272
RTABMapApp::clearMeasures
void clearMeasures()
Definition: RTABMapApp.cpp:4405
UEventsHandler.h
RTABMapApp::postExportation
bool postExportation(bool visualize)
Definition: RTABMapApp.cpp:4093
RTABMapApp::openDatabase
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
Definition: RTABMapApp.cpp:392
RTABMapApp::minCloudDepth_
float minCloudDepth_
Definition: RTABMapApp.h:244
RTABMapApp::showMeasures
void showMeasures(bool x, bool y, bool z, bool custom)
env
RTABMapApp::setExportPointCloudFormat
void setExportPointCloudFormat(const std::string &format)
Definition: RTABMapApp.cpp:3117
USemaphore
Definition: USemaphore.h:54
RTABMapApp::depthFromMotion_
bool depthFromMotion_
Definition: RTABMapApp.h:238
RTABMapApp::gainCompensationOnNextRender_
int gainCompensationOnNextRender_
Definition: RTABMapApp.h:265
RTABMapApp::backgroundColor_
float backgroundColor_
Definition: RTABMapApp.h:252
RTABMapApp::screenshotReady_
USemaphore screenshotReady_
Definition: RTABMapApp.h:318
RTABMapApp::fpsTime_
UTimer fpsTime_
Definition: RTABMapApp.h:303
rtabmap::CameraMobile
Definition: CameraMobile.h:71
RTABMapApp::setFOV
void setFOV(float angle)
Definition: RTABMapApp.cpp:2896
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:4465
RTABMapApp::optMesh_
rtabmap::Mesh optMesh_
Definition: RTABMapApp.h:281
RTABMapApp::setGPS
void setGPS(const rtabmap::GPS &gps)
Definition: RTABMapApp.cpp:3177
RTABMapApp::status_
std::pair< rtabmap::RtabmapEventInit::Status, std::string > status_
Definition: RTABMapApp.h:323
UTimer
Definition: UTimer.h:46
RTABMapApp::smoothMesh
bool smoothMesh(int id, rtabmap::Mesh &mesh)
Definition: RTABMapApp.cpp:1195
float
float
RTABMapApp::totalPolygons_
int totalPolygons_
Definition: RTABMapApp.h:270
p22
p22
RTABMapApp::setPausedMapping
void setPausedMapping(bool paused)
Definition: RTABMapApp.cpp:2850
RTABMapApp::optTexture_
cv::Mat optTexture_
Definition: RTABMapApp.h:280
rtabmap::Rtabmap
Definition: Rtabmap.h:54
RTABMapApp::dataRecorderMode_
bool dataRecorderMode_
Definition: RTABMapApp.h:259
RTABMapApp::meshAngleToleranceDeg_
float meshAngleToleranceDeg_
Definition: RTABMapApp.h:247
ProgressionStatus.h
RTABMapApp::Render
int Render()
Definition: RTABMapApp.cpp:1316
RTABMapApp::optRefPose_
rtabmap::Transform * optRefPose_
Definition: RTABMapApp.h:283
RTABMapApp::rawPoses_
std::map< int, rtabmap::Transform > rawPoses_
Definition: RTABMapApp.h:321
RTABMapApp::meshDecimationFactor_
float meshDecimationFactor_
Definition: RTABMapApp.h:248
RTABMapApp::depthConfidence_
int depthConfidence_
Definition: RTABMapApp.h:253
RTABMapApp::startCamera
bool startCamera()
Definition: RTABMapApp.cpp:930
RTABMapApp::poseEvents_
std::list< rtabmap::Transform > poseEvents_
Definition: RTABMapApp.h:307
RTABMapApp::metricSystem_
bool metricSystem_
Definition: RTABMapApp.h:286
RTABMapApp::InitializeGLContent
void InitializeGLContent()
Definition: RTABMapApp.cpp:1154
RTABMapApp::setMeshRendering
void setMeshRendering(bool enabled, bool withTexture)
Definition: RTABMapApp.cpp:2888
RTABMapApp::measuringTextSize_
float measuringTextSize_
Definition: RTABMapApp.h:287
value
value
RTABMapApp::setNodesFiltering
void setNodesFiltering(bool enabled)
Definition: RTABMapApp.cpp:2970
RTABMapApp::camera_
rtabmap::CameraMobile * camera_
Definition: RTABMapApp.h:225
conf
RTABMapApp::setOdomCloudShown
void setOdomCloudShown(bool shown)
Definition: RTABMapApp.cpp:2883
RTABMapApp::lastDrawnCloudsCount_
int lastDrawnCloudsCount_
Definition: RTABMapApp.h:271
RTABMapApp::lastPoseEventTime_
double lastPoseEventTime_
Definition: RTABMapApp.h:274
RTABMapApp::addEnvSensor
void addEnvSensor(int type, float value)
Definition: RTABMapApp.cpp:3186
RTABMapApp::meshesMutex_
boost::mutex meshesMutex_
Definition: RTABMapApp.h:313
RTABMapApp::setMeasuringMode
void setMeasuringMode(int mode)
Definition: RTABMapApp.cpp:4412
RTABMapApp::measures_
std::list< Measure > measures_
Definition: RTABMapApp.h:284
rtabmap::RtabmapThread
Definition: RtabmapThread.h:51
RTABMapApp::cameraMutex_
boost::mutex cameraMutex_
Definition: RTABMapApp.h:311
RTABMapApp::swiftClassPtr_
void * swiftClassPtr_
Definition: RTABMapApp.h:328
RTABMapApp::addMeasureClicked_
bool addMeasureClicked_
Definition: RTABMapApp.h:291
RTABMapApp::setTrajectoryMode
void setTrajectoryMode(bool enabled)
Definition: RTABMapApp.cpp:2942


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:59