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_client_api.h> // NOLINT
35 #include <tango-gl/util.h>
36 
37 #include "scene.h"
38 #include "CameraTango.h"
39 #include "util.h"
40 #include "ProgressionStatus.h"
41 
44 #include <boost/thread/mutex.hpp>
45 #include <pcl/pcl_base.h>
46 #include <pcl/TextureMesh.h>
47 
48 // RTABMapApp handles the application lifecycle and resources.
49 class RTABMapApp : public UEventsHandler {
50  public:
51  // Constructor and deconstructor.
52  RTABMapApp();
53  ~RTABMapApp();
54 
55  void onCreate(JNIEnv* env, jobject caller_activity);
56 
57  void setScreenRotation(int displayRotation, int cameraRotation);
58 
59  int openDatabase(const std::string & databasePath, bool databaseInMemory, bool optimize, const std::string & databaseSource=std::string());
60 
61  bool onTangoServiceConnected(JNIEnv* env, jobject iBinder);
62 
63  // Explicitly reset motion tracking and restart the pipeline.
64  // Note that this will cause motion tracking to re-initialize.
66 
67  // Tango Service point cloud callback function for depth data. Called when new
68  // new point cloud data is available from the Tango Service.
69  //
70  // @param pose: The current point cloud returned by the service,
71  // caller allocated.
72  void onPointCloudAvailable(const TangoXYZij* xyz_ij);
73 
74  // Tango service pose callback function for pose data. Called when new
75  // information about device pose is available from the Tango Service.
76  //
77  // @param pose: The current pose returned by the service, caller allocated.
78  void onPoseAvailable(const TangoPoseData* pose);
79 
80  // Tango service event callback function for event data. Called when new events
81  // are available from the Tango Service.
82  //
83  // @param event: Tango event, caller allocated.
84  void onTangoEventAvailable(const TangoEvent* event);
85 
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  // Release all non-OpenGL allocated resources.
96  void onPause();
97 
98  // Set render camera's viewing angle, first person, third person or top down.
99  //
100  // @param: camera_type, camera type includes first person, third person and
101  // top down
103 
104  // Touch event passed from android activity. This function only supports two
105  // touches.
106  //
107  // @param: touch_count, total count for touches.
108  // @param: event, touch event of current touch.
109  // @param: x0, normalized touch location for touch 0 on x axis.
110  // @param: y0, normalized touch location for touch 0 on y axis.
111  // @param: x1, normalized touch location for touch 1 on x axis.
112  // @param: y1, normalized touch location for touch 1 on y axis.
113  void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event,
114  float x0, float y0, float x1, float y1);
115 
116  void setPausedMapping(bool paused);
117  void setOnlineBlending(bool enabled);
118  void setMapCloudShown(bool shown);
119  void setOdomCloudShown(bool shown);
120  void setMeshRendering(bool enabled, bool withTexture);
121  void setPointSize(float value);
122  void setFOV(float angle);
123  void setOrthoCropFactor(float value);
124  void setGridRotation(float value);
125  void setLighting(bool enabled);
126  void setBackfaceCulling(bool enabled);
127  void setWireframe(bool enabled);
128  void setLocalizationMode(bool enabled);
129  void setTrajectoryMode(bool enabled);
130  void setGraphOptimization(bool enabled);
131  void setNodesFiltering(bool enabled);
132  void setGraphVisible(bool visible);
133  void setGridVisible(bool visible);
134  void setRawScanSaved(bool enabled);
135  void setCameraColor(bool enabled);
136  void setFullResolution(bool enabled);
137  void setSmoothing(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 setMeshTriangleSize(int value);
145  void setClusterRatio(float value);
146  void setMaxGainRadius(float value);
147  void setRenderingTextureDecimation(int value);
148  void setBackgroundColor(float gray);
149  int setMappingParameter(const std::string & key, const std::string & value);
150  void setGPS(const rtabmap::GPS & gps);
151 
152  void resetMapping();
153  void save(const std::string & databasePath);
154  void cancelProcessing();
155  bool exportMesh(
156  float cloudVoxelSize,
157  bool regenerateCloud,
158  bool meshing,
159  int textureSize,
160  int textureCount,
161  int normalK,
162  bool optimized,
163  float optimizedVoxelSize,
164  int optimizedDepth,
165  int optimizedMaxPolygons,
166  float optimizedColorRadius,
167  bool optimizedCleanWhitePolygons,
168  int optimizedMinClusterSize,
169  float optimizedMaxTextureDistance,
170  int optimizedMinTextureClusterSize,
171  bool blockRendering);
172  bool postExportation(bool visualize);
173  bool writeExportedMesh(const std::string & directory, const std::string & name);
174  int postProcessing(int approach);
175 
176  protected:
177  virtual bool handleEvent(UEvent * event);
178 
179  private:
181  bool smoothMesh(int id, Mesh & mesh);
182  void gainCompensation(bool full = false);
183  std::vector<pcl::Vertices> filterOrganizedPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
184  std::vector<pcl::Vertices> filterPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
185 
186  private:
191 
211 
213 
214  bool paused_;
232  std::map<std::string, float> bufferedStatsData_;
233 
236  pcl::TextureMesh::Ptr optMesh_;
237  cv::Mat optTexture_;
239  rtabmap::Transform * optRefPose_; // App crashes when loading native library if not dynamic
240 
241  // main_scene_ includes all drawable object for visualizing Tango device's
242  // movement and point cloud.
244 
245  std::list<rtabmap::RtabmapEvent*> rtabmapEvents_;
246  std::list<rtabmap::RtabmapEvent*> visLocalizationEvents_;
247  std::list<rtabmap::OdometryEvent> odomEvents_;
248  std::list<rtabmap::Transform> poseEvents_;
249 
251 
252  boost::mutex rtabmapMutex_;
253  boost::mutex visLocalizationMutex_;
254  boost::mutex meshesMutex_;
255  boost::mutex odomMutex_;
256  boost::mutex poseMutex_;
257  boost::mutex renderingMutex_;
258 
260 
261  std::map<int, Mesh> createdMeshes_;
262  std::map<int, rtabmap::Transform> rawPoses_;
263 
264  std::pair<rtabmap::RtabmapEventInit::Status, std::string> status_;
265 
267 };
268 
269 #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 onCreate(JNIEnv *env, jobject caller_activity)
Definition: RTABMapApp.cpp:241
void setCameraColor(bool enabled)
Scene main_scene_
Definition: RTABMapApp.h:243
void setMaxGainRadius(float value)
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, const std::string &databaseSource=std::string())
Definition: RTABMapApp.cpp:294
void setWireframe(bool enabled)
float clusterRatio_
Definition: RTABMapApp.h:207
void setAppendMode(bool enabled)
int setMappingParameter(const std::string &key, const std::string &value)
void SetViewPort(int width, int height)
Definition: RTABMapApp.cpp:852
double lastPoseEventTime_
Definition: RTABMapApp.h:231
bool appendMode_
Definition: RTABMapApp.h:201
void setSmoothing(bool enabled)
Definition: UEvent.h:57
bool trajectoryMode_
Definition: RTABMapApp.h:196
int lastDrawnCloudsCount_
Definition: RTABMapApp.h:228
boost::mutex poseMutex_
Definition: RTABMapApp.h:256
std::vector< pcl::Vertices > filterOrganizedPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:732
Definition: lz4.c:365
void setGraphOptimization(bool enabled)
float renderingTime_
Definition: RTABMapApp.h:229
std::map< int, Mesh > createdMeshes_
Definition: RTABMapApp.h:261
bool onTangoServiceConnected(JNIEnv *env, jobject iBinder)
Definition: RTABMapApp.cpp:623
bool localizationMode_
Definition: RTABMapApp.h:195
void setGraphVisible(bool visible)
bool fullResolution_
Definition: RTABMapApp.h:200
bool exporting_
Definition: RTABMapApp.h:218
rtabmap::ParametersMap getRtabmapParameters()
Definition: RTABMapApp.cpp:73
void onPoseAvailable(const TangoPoseData *pose)
boost::mutex visLocalizationMutex_
Definition: RTABMapApp.h:253
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
Definition: util.h:147
bool paused_
Definition: RTABMapApp.h:214
std::vector< pcl::Vertices > filterPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
Definition: RTABMapApp.cpp:799
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
std::map< std::string, float > bufferedStatsData_
Definition: RTABMapApp.h:232
bool dataRecorderMode_
Definition: RTABMapApp.h:215
int optRefId_
Definition: RTABMapApp.h:238
std::list< rtabmap::RtabmapEvent * > rtabmapEvents_
Definition: RTABMapApp.h:245
float maxGainRadius_
Definition: RTABMapApp.h:208
void setCloudDensityLevel(int value)
bool smoothMesh(int id, Mesh &mesh)
Definition: RTABMapApp.cpp:879
void InitializeGLContent()
Definition: RTABMapApp.cpp:842
int postProcessing(int approach)
pcl::TextureMesh::Ptr optMesh_
Definition: RTABMapApp.h:236
void setRenderingTextureDecimation(int value)
float minCloudDepth_
Definition: RTABMapApp.h:203
void setClusterRatio(float value)
void setOrthoCropFactor(float value)
bool visualizingMesh_
Definition: RTABMapApp.h:234
void setGPS(const rtabmap::GPS &gps)
int meshDecimation_
Definition: RTABMapApp.h:225
bool nodesFiltering_
Definition: RTABMapApp.h:194
void setPointSize(float value)
bool filterPolygonsOnNextRender_
Definition: RTABMapApp.h:220
bool takeScreenshotOnNextRender_
Definition: RTABMapApp.h:223
bool rawScanSaved_
Definition: RTABMapApp.h:197
boost::mutex rtabmapMutex_
Definition: RTABMapApp.h:252
bool cameraColor_
Definition: RTABMapApp.h:199
bool clearSceneOnNextRender_
Definition: RTABMapApp.h:216
void setTrajectoryMode(bool enabled)
int cloudDensityLevel_
Definition: RTABMapApp.h:204
virtual bool handleEvent(UEvent *event)
boost::mutex odomMutex_
Definition: RTABMapApp.h:255
void setFOV(float angle)
std::map< int, rtabmap::Transform > rawPoses_
Definition: RTABMapApp.h:262
void setMaxCloudDepth(float value)
void setGridRotation(float value)
int renderingTextureDecimation_
Definition: RTABMapApp.h:209
void setBackfaceCulling(bool enabled)
void setRawScanSaved(bool enabled)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
void TangoResetMotionTracking()
Definition: RTABMapApp.cpp:728
int gainCompensationOnNextRender_
Definition: RTABMapApp.h:221
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:254
double lastPostRenderEventTime_
Definition: RTABMapApp.h:230
void setMapCloudShown(bool shown)
bool postProcessing_
Definition: RTABMapApp.h:219
rtabmap::RtabmapThread * rtabmapThread_
Definition: RTABMapApp.h:188
float backgroundColor_
Definition: RTABMapApp.h:210
cv::Mat optTexture_
Definition: RTABMapApp.h:237
LogHandler * logHandler_
Definition: RTABMapApp.h:190
void setMinCloudDepth(float value)
Definition: scene.h:46
rtabmap::Transform mapToOdom_
Definition: RTABMapApp.h:250
std::pair< rtabmap::RtabmapEventInit::Status, std::string > status_
Definition: RTABMapApp.h:264
void setOnlineBlending(bool enabled)
bool exportedMeshUpdated_
Definition: RTABMapApp.h:235
bool odomCloudShown_
Definition: RTABMapApp.h:192
void gainCompensation(bool full=false)
Definition: RTABMapApp.cpp:944
void setDataRecorderMode(bool enabled)
bool smoothing_
Definition: RTABMapApp.h:198
bool writeExportedMesh(const std::string &directory, const std::string &name)
bool cameraJustInitialized_
Definition: RTABMapApp.h:224
boost::mutex renderingMutex_
Definition: RTABMapApp.h:257
void resetMapping()
void onPause()
Definition: RTABMapApp.cpp:717
void setMeshTriangleSize(int value)
int meshTrianglePix_
Definition: RTABMapApp.h:205
bool openingDatabase_
Definition: RTABMapApp.h:217
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:226
float meshAngleToleranceDeg_
Definition: RTABMapApp.h:206
std::list< rtabmap::Transform > poseEvents_
Definition: RTABMapApp.h:248
USemaphore screenshotReady_
Definition: RTABMapApp.h:259
void setFullResolution(bool enabled)
float maxCloudDepth_
Definition: RTABMapApp.h:202
void setMeshAngleTolerance(float value)
std::list< rtabmap::OdometryEvent > odomEvents_
Definition: RTABMapApp.h:247
void setScreenRotation(int displayRotation, int cameraRotation)
Definition: RTABMapApp.cpp:286
rtabmap::Rtabmap * rtabmap_
Definition: RTABMapApp.h:189
bool bilateralFilteringOnNextRender_
Definition: RTABMapApp.h:222
rtabmap::ParametersMap mappingParameters_
Definition: RTABMapApp.h:212
rtabmap::ProgressionStatus progressionStatus_
Definition: RTABMapApp.h:266
void onTangoEventAvailable(const TangoEvent *event)
void setLighting(bool enabled)
bool graphOptimization_
Definition: RTABMapApp.h:193
rtabmap::Transform * optRefPose_
Definition: RTABMapApp.h:239
int totalPolygons_
Definition: RTABMapApp.h:227
rtabmap::CameraTango * camera_
Definition: RTABMapApp.h:187
void onPointCloudAvailable(const TangoXYZij *xyz_ij)
void setPausedMapping(bool paused)
void setOdomCloudShown(bool shown)
std::list< rtabmap::RtabmapEvent * > visLocalizationEvents_
Definition: RTABMapApp.h:246
void setLocalizationMode(bool enabled)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32