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 #include <jni.h>
32 #include <memory>
33 
34 #include <tango-gl/util.h>
35 
36 #include "scene.h"
37 #include "CameraMobile.h"
38 #include "util.h"
39 #include "ProgressionStatus.h"
40 
43 #include <boost/thread/mutex.hpp>
44 #include <pcl/pcl_base.h>
45 #include <pcl/TextureMesh.h>
46 
47 
48 // RTABMapApp handles the application lifecycle and resources.
49 class RTABMapApp : public UEventsHandler {
50  public:
51  // Constructor and deconstructor.
52  RTABMapApp(JNIEnv* env, jobject caller_activity);
53  ~RTABMapApp();
54 
55  void setScreenRotation(int displayRotation, int cameraRotation);
56 
57  int openDatabase(const std::string & databasePath, bool databaseInMemory, bool optimize, const std::string & databaseSource=std::string());
58 
59  bool isBuiltWith(int cameraDriver) const;
60  bool startCamera(JNIEnv* env, jobject iBinder, jobject context, jobject activity, int driver);
61 
62  // Allocate OpenGL resources for rendering, mainly for initializing the Scene.
63  void InitializeGLContent();
64 
65  // Setup the view port width and height.
66  void SetViewPort(int width, int height);
67 
68  // Main render loop.
69  int Render();
70 
71  void stopCamera();
72 
73  // Set render camera's viewing angle, first person, third person or top down.
74  //
75  // @param: camera_type, camera type includes first person, third person and
76  // top down
78 
79  // Touch event passed from android activity. This function only supports two
80  // touches.
81  //
82  // @param: touch_count, total count for touches.
83  // @param: event, touch event of current touch.
84  // @param: x0, normalized touch location for touch 0 on x axis.
85  // @param: y0, normalized touch location for touch 0 on y axis.
86  // @param: x1, normalized touch location for touch 1 on x axis.
87  // @param: y1, normalized touch location for touch 1 on y axis.
88  void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event,
89  float x0, float y0, float x1, float y1);
90 
91  void setPausedMapping(bool paused);
92  void setOnlineBlending(bool enabled);
93  void setMapCloudShown(bool shown);
94  void setOdomCloudShown(bool shown);
95  void setMeshRendering(bool enabled, bool withTexture);
96  void setPointSize(float value);
97  void setFOV(float angle);
98  void setOrthoCropFactor(float value);
99  void setGridRotation(float value);
100  void setLighting(bool enabled);
101  void setBackfaceCulling(bool enabled);
102  void setWireframe(bool enabled);
103  void setLocalizationMode(bool enabled);
104  void setTrajectoryMode(bool enabled);
105  void setGraphOptimization(bool enabled);
106  void setNodesFiltering(bool enabled);
107  void setGraphVisible(bool visible);
108  void setGridVisible(bool visible);
109  void setRawScanSaved(bool enabled);
110  void setCameraColor(bool enabled);
111  void setFullResolution(bool enabled);
112  void setSmoothing(bool enabled);
113  void setDepthFromMotion(bool enabled);
114  void setAppendMode(bool enabled);
115  void setDataRecorderMode(bool enabled);
116  void setMaxCloudDepth(float value);
117  void setMinCloudDepth(float value);
118  void setCloudDensityLevel(int value);
119  void setMeshAngleTolerance(float value);
120  void setMeshTriangleSize(int value);
121  void setClusterRatio(float value);
122  void setMaxGainRadius(float value);
123  void setRenderingTextureDecimation(int value);
124  void setBackgroundColor(float gray);
125  int setMappingParameter(const std::string & key, const std::string & value);
126  void setGPS(const rtabmap::GPS & gps);
127  void addEnvSensor(int type, float value);
128 
129  void save(const std::string & databasePath);
130  void cancelProcessing();
131  bool exportMesh(
132  float cloudVoxelSize,
133  bool regenerateCloud,
134  bool meshing,
135  int textureSize,
136  int textureCount,
137  int normalK,
138  bool optimized,
139  float optimizedVoxelSize,
140  int optimizedDepth,
141  int optimizedMaxPolygons,
142  float optimizedColorRadius,
143  bool optimizedCleanWhitePolygons,
144  int optimizedMinClusterSize,
145  float optimizedMaxTextureDistance,
146  int optimizedMinTextureClusterSize,
147  bool blockRendering);
148  bool postExportation(bool visualize);
149  bool writeExportedMesh(const std::string & directory, const std::string & name);
150  int postProcessing(int approach);
151 
152  void postCameraPoseEvent(
153  float x, float y, float z, float qx, float qy, float qz, float qw);
154 
155  void postOdometryEvent(
156  float x, float y, float z, float qx, float qy, float qz, float qw,
157  float fx, float fy, float cx, float cy,
158  double stamp,
159  void * yPlane, void * uPlane, void * vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat,
160  void * depth, int depthLen, int depthWidth, int depthHeight, int depthFormat,
161  float * points, int pointsLen);
162 
163  protected:
164  virtual bool handleEvent(UEvent * event);
165 
166  private:
168  bool smoothMesh(int id, rtabmap::Mesh & mesh);
169  void gainCompensation(bool full = false);
170  std::vector<pcl::Vertices> filterOrganizedPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
171  std::vector<pcl::Vertices> filterPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
172 
173  private:
179 
200 
202 
220  std::map<std::string, float> bufferedStatsData_;
221 
224  pcl::TextureMesh::Ptr optMesh_;
225  cv::Mat optTexture_;
227  rtabmap::Transform * optRefPose_; // App crashes when loading native library if not dynamic
228 
229  // main_scene_ includes all drawable object for visualizing Tango device's
230  // movement and point cloud.
232 
233  std::list<rtabmap::RtabmapEvent*> rtabmapEvents_;
234  std::list<rtabmap::OdometryEvent> odomEvents_;
235  std::list<rtabmap::Transform> poseEvents_;
236 
238 
239  boost::mutex cameraMutex_;
240  boost::mutex rtabmapMutex_;
241  boost::mutex meshesMutex_;
242  boost::mutex odomMutex_;
243  boost::mutex poseMutex_;
244  boost::mutex renderingMutex_;
245 
247 
248  std::map<int, rtabmap::Mesh> createdMeshes_;
249  std::map<int, rtabmap::Transform> rawPoses_;
250 
251  std::pair<rtabmap::RtabmapEventInit::Status, std::string> status_;
252 
254 };
255 
256 #endif // TANGO_POINT_CLOUD_POINT_CLOUD_APP_H_
void save(const std::string &databasePath)
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:231
void setMaxGainRadius(float value)
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, const std::string &databaseSource=std::string())
Definition: RTABMapApp.cpp:271
void setWireframe(bool enabled)
float clusterRatio_
Definition: RTABMapApp.h:196
void setAppendMode(bool enabled)
rtabmap::LogHandler * logHandler_
Definition: RTABMapApp.h:178
int setMappingParameter(const std::string &key, const std::string &value)
void SetViewPort(int width, int height)
Definition: RTABMapApp.cpp:940
double lastPoseEventTime_
Definition: RTABMapApp.h:219
bool appendMode_
Definition: RTABMapApp.h:190
void setSmoothing(bool enabled)
Definition: UEvent.h:57
bool trajectoryMode_
Definition: RTABMapApp.h:184
int lastDrawnCloudsCount_
Definition: RTABMapApp.h:216
void postCameraPoseEvent(float x, float y, float z, float qx, float qy, float qz, float qw)
boost::mutex poseMutex_
Definition: RTABMapApp.h:243
std::vector< pcl::Vertices > filterOrganizedPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:820
Definition: lz4.c:365
void setGraphOptimization(bool enabled)
float renderingTime_
Definition: RTABMapApp.h:217
bool localizationMode_
Definition: RTABMapApp.h:183
void setGraphVisible(bool visible)
bool fullResolution_
Definition: RTABMapApp.h:189
bool exporting_
Definition: RTABMapApp.h:206
rtabmap::ParametersMap getRtabmapParameters()
Definition: RTABMapApp.cpp:81
void setDepthFromMotion(bool enabled)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
std::vector< pcl::Vertices > filterPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:887
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
std::map< std::string, float > bufferedStatsData_
Definition: RTABMapApp.h:220
bool dataRecorderMode_
Definition: RTABMapApp.h:203
int optRefId_
Definition: RTABMapApp.h:226
std::list< rtabmap::RtabmapEvent * > rtabmapEvents_
Definition: RTABMapApp.h:233
float maxGainRadius_
Definition: RTABMapApp.h:197
void setCloudDensityLevel(int value)
void InitializeGLContent()
Definition: RTABMapApp.cpp:930
int postProcessing(int approach)
pcl::TextureMesh::Ptr optMesh_
Definition: RTABMapApp.h:224
void setRenderingTextureDecimation(int value)
float minCloudDepth_
Definition: RTABMapApp.h:192
void setClusterRatio(float value)
void setOrthoCropFactor(float value)
bool visualizingMesh_
Definition: RTABMapApp.h:222
void setGPS(const rtabmap::GPS &gps)
int meshDecimation_
Definition: RTABMapApp.h:213
bool nodesFiltering_
Definition: RTABMapApp.h:182
void setPointSize(float value)
bool filterPolygonsOnNextRender_
Definition: RTABMapApp.h:208
bool takeScreenshotOnNextRender_
Definition: RTABMapApp.h:211
bool rawScanSaved_
Definition: RTABMapApp.h:185
boost::mutex rtabmapMutex_
Definition: RTABMapApp.h:240
bool cameraColor_
Definition: RTABMapApp.h:188
bool clearSceneOnNextRender_
Definition: RTABMapApp.h:204
void setTrajectoryMode(bool enabled)
int cloudDensityLevel_
Definition: RTABMapApp.h:193
bool startCamera(JNIEnv *env, jobject iBinder, jobject context, jobject activity, int driver)
Definition: RTABMapApp.cpp:659
virtual bool handleEvent(UEvent *event)
boost::mutex odomMutex_
Definition: RTABMapApp.h:242
void setFOV(float angle)
std::map< int, rtabmap::Transform > rawPoses_
Definition: RTABMapApp.h:249
void setMaxCloudDepth(float value)
void setGridRotation(float value)
int renderingTextureDecimation_
Definition: RTABMapApp.h:198
void setBackfaceCulling(bool enabled)
void setRawScanSaved(bool enabled)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
bool isBuiltWith(int cameraDriver) const
Definition: RTABMapApp.cpp:628
void postOdometryEvent(float x, float y, float z, float qx, float qy, float qz, float qw, float fx, float fy, float cx, float cy, double stamp, void *yPlane, void *uPlane, void *vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, void *depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, float *points, int pointsLen)
int gainCompensationOnNextRender_
Definition: RTABMapApp.h:209
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:241
double lastPostRenderEventTime_
Definition: RTABMapApp.h:218
void setMapCloudShown(bool shown)
bool postProcessing_
Definition: RTABMapApp.h:207
rtabmap::RtabmapThread * rtabmapThread_
Definition: RTABMapApp.h:176
boost::mutex cameraMutex_
Definition: RTABMapApp.h:239
float backgroundColor_
Definition: RTABMapApp.h:199
cv::Mat optTexture_
Definition: RTABMapApp.h:225
void setMinCloudDepth(float value)
Definition: scene.h:47
rtabmap::Transform mapToOdom_
Definition: RTABMapApp.h:237
std::pair< rtabmap::RtabmapEventInit::Status, std::string > status_
Definition: RTABMapApp.h:251
void setOnlineBlending(bool enabled)
bool exportedMeshUpdated_
Definition: RTABMapApp.h:223
bool odomCloudShown_
Definition: RTABMapApp.h:180
std::map< int, rtabmap::Mesh > createdMeshes_
Definition: RTABMapApp.h:248
void gainCompensation(bool full=false)
void setDataRecorderMode(bool enabled)
bool smoothing_
Definition: RTABMapApp.h:186
bool writeExportedMesh(const std::string &directory, const std::string &name)
bool cameraJustInitialized_
Definition: RTABMapApp.h:212
void stopCamera()
Definition: RTABMapApp.cpp:805
boost::mutex renderingMutex_
Definition: RTABMapApp.h:244
void setMeshTriangleSize(int value)
int meshTrianglePix_
Definition: RTABMapApp.h:194
bool openingDatabase_
Definition: RTABMapApp.h:205
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:214
RTABMapApp(JNIEnv *env, jobject caller_activity)
Definition: RTABMapApp.cpp:156
float meshAngleToleranceDeg_
Definition: RTABMapApp.h:195
std::list< rtabmap::Transform > poseEvents_
Definition: RTABMapApp.h:235
bool smoothMesh(int id, rtabmap::Mesh &mesh)
Definition: RTABMapApp.cpp:972
USemaphore screenshotReady_
Definition: RTABMapApp.h:246
bool depthFromMotion_
Definition: RTABMapApp.h:187
void setFullResolution(bool enabled)
float maxCloudDepth_
Definition: RTABMapApp.h:191
void setMeshAngleTolerance(float value)
std::list< rtabmap::OdometryEvent > odomEvents_
Definition: RTABMapApp.h:234
void addEnvSensor(int type, float value)
void setScreenRotation(int displayRotation, int cameraRotation)
Definition: RTABMapApp.cpp:258
rtabmap::Rtabmap * rtabmap_
Definition: RTABMapApp.h:177
bool bilateralFilteringOnNextRender_
Definition: RTABMapApp.h:210
rtabmap::ParametersMap mappingParameters_
Definition: RTABMapApp.h:201
rtabmap::ProgressionStatus progressionStatus_
Definition: RTABMapApp.h:253
void setLighting(bool enabled)
rtabmap::CameraMobile * camera_
Definition: RTABMapApp.h:175
bool graphOptimization_
Definition: RTABMapApp.h:181
rtabmap::Transform * optRefPose_
Definition: RTABMapApp.h:227
int cameraDriver_
Definition: RTABMapApp.h:174
int totalPolygons_
Definition: RTABMapApp.h:215
void setPausedMapping(bool paused)
void setOdomCloudShown(bool shown)
void setLocalizationMode(bool enabled)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:35:00