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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:30