Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef RTABMAP_APP_H_
00029 #define RTABMAP_APP_H_
00030
00031 #include <jni.h>
00032 #include <memory>
00033
00034 #include <tango_client_api.h>
00035 #include <tango-gl/util.h>
00036
00037 #include "scene.h"
00038 #include "CameraTango.h"
00039 #include "util.h"
00040 #include "ProgressionStatus.h"
00041
00042 #include <rtabmap/core/RtabmapThread.h>
00043 #include <rtabmap/utilite/UEventsHandler.h>
00044 #include <boost/thread/mutex.hpp>
00045 #include <pcl/pcl_base.h>
00046 #include <pcl/TextureMesh.h>
00047
00048
00049 class RTABMapApp : public UEventsHandler {
00050 public:
00051
00052 RTABMapApp();
00053 ~RTABMapApp();
00054
00055 void onCreate(JNIEnv* env, jobject caller_activity);
00056
00057 void setScreenRotation(int displayRotation, int cameraRotation);
00058
00059 int openDatabase(const std::string & databasePath, bool databaseInMemory, bool optimize, const std::string & databaseSource=std::string());
00060
00061 bool onTangoServiceConnected(JNIEnv* env, jobject iBinder);
00062
00063
00064
00065 void TangoResetMotionTracking();
00066
00067
00068
00069
00070
00071
00072 void onPointCloudAvailable(const TangoXYZij* xyz_ij);
00073
00074
00075
00076
00077
00078 void onPoseAvailable(const TangoPoseData* pose);
00079
00080
00081
00082
00083
00084 void onTangoEventAvailable(const TangoEvent* event);
00085
00086
00087 void InitializeGLContent();
00088
00089
00090 void SetViewPort(int width, int height);
00091
00092
00093 int Render();
00094
00095
00096 void onPause();
00097
00098
00099
00100
00101
00102 void SetCameraType(tango_gl::GestureCamera::CameraType camera_type);
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113 void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event,
00114 float x0, float y0, float x1, float y1);
00115
00116 void setPausedMapping(bool paused);
00117 void setOnlineBlending(bool enabled);
00118 void setMapCloudShown(bool shown);
00119 void setOdomCloudShown(bool shown);
00120 void setMeshRendering(bool enabled, bool withTexture);
00121 void setPointSize(float value);
00122 void setFOV(float angle);
00123 void setOrthoCropFactor(float value);
00124 void setGridRotation(float value);
00125 void setLighting(bool enabled);
00126 void setBackfaceCulling(bool enabled);
00127 void setWireframe(bool enabled);
00128 void setLocalizationMode(bool enabled);
00129 void setTrajectoryMode(bool enabled);
00130 void setGraphOptimization(bool enabled);
00131 void setNodesFiltering(bool enabled);
00132 void setGraphVisible(bool visible);
00133 void setGridVisible(bool visible);
00134 void setRawScanSaved(bool enabled);
00135 void setCameraColor(bool enabled);
00136 void setFullResolution(bool enabled);
00137 void setSmoothing(bool enabled);
00138 void setAppendMode(bool enabled);
00139 void setDataRecorderMode(bool enabled);
00140 void setMaxCloudDepth(float value);
00141 void setMinCloudDepth(float value);
00142 void setCloudDensityLevel(int value);
00143 void setMeshAngleTolerance(float value);
00144 void setMeshTriangleSize(int value);
00145 void setClusterRatio(float value);
00146 void setMaxGainRadius(float value);
00147 void setRenderingTextureDecimation(int value);
00148 void setBackgroundColor(float gray);
00149 int setMappingParameter(const std::string & key, const std::string & value);
00150 void setGPS(const rtabmap::GPS & gps);
00151
00152 void resetMapping();
00153 void save(const std::string & databasePath);
00154 void cancelProcessing();
00155 bool exportMesh(
00156 float cloudVoxelSize,
00157 bool regenerateCloud,
00158 bool meshing,
00159 int textureSize,
00160 int textureCount,
00161 int normalK,
00162 bool optimized,
00163 float optimizedVoxelSize,
00164 int optimizedDepth,
00165 int optimizedMaxPolygons,
00166 float optimizedColorRadius,
00167 bool optimizedCleanWhitePolygons,
00168 int optimizedMinClusterSize,
00169 float optimizedMaxTextureDistance,
00170 int optimizedMinTextureClusterSize,
00171 bool blockRendering);
00172 bool postExportation(bool visualize);
00173 bool writeExportedMesh(const std::string & directory, const std::string & name);
00174 int postProcessing(int approach);
00175
00176 protected:
00177 virtual bool handleEvent(UEvent * event);
00178
00179 private:
00180 rtabmap::ParametersMap getRtabmapParameters();
00181 bool smoothMesh(int id, Mesh & mesh);
00182 void gainCompensation(bool full = false);
00183 std::vector<pcl::Vertices> filterOrganizedPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
00184 std::vector<pcl::Vertices> filterPolygons(const std::vector<pcl::Vertices> & polygons, int cloudSize) const;
00185
00186 private:
00187 rtabmap::CameraTango * camera_;
00188 rtabmap::RtabmapThread * rtabmapThread_;
00189 rtabmap::Rtabmap * rtabmap_;
00190 LogHandler * logHandler_;
00191
00192 bool odomCloudShown_;
00193 bool graphOptimization_;
00194 bool nodesFiltering_;
00195 bool localizationMode_;
00196 bool trajectoryMode_;
00197 bool rawScanSaved_;
00198 bool smoothing_;
00199 bool cameraColor_;
00200 bool fullResolution_;
00201 bool appendMode_;
00202 float maxCloudDepth_;
00203 float minCloudDepth_;
00204 int cloudDensityLevel_;
00205 int meshTrianglePix_;
00206 float meshAngleToleranceDeg_;
00207 float clusterRatio_;
00208 float maxGainRadius_;
00209 int renderingTextureDecimation_;
00210 float backgroundColor_;
00211
00212 rtabmap::ParametersMap mappingParameters_;
00213
00214 bool paused_;
00215 bool dataRecorderMode_;
00216 bool clearSceneOnNextRender_;
00217 bool openingDatabase_;
00218 bool exporting_;
00219 bool postProcessing_;
00220 bool filterPolygonsOnNextRender_;
00221 int gainCompensationOnNextRender_;
00222 bool bilateralFilteringOnNextRender_;
00223 bool takeScreenshotOnNextRender_;
00224 bool cameraJustInitialized_;
00225 int meshDecimation_;
00226 int totalPoints_;
00227 int totalPolygons_;
00228 int lastDrawnCloudsCount_;
00229 float renderingTime_;
00230 double lastPostRenderEventTime_;
00231 double lastPoseEventTime_;
00232 std::map<std::string, float> bufferedStatsData_;
00233
00234 bool visualizingMesh_;
00235 bool exportedMeshUpdated_;
00236 pcl::TextureMesh::Ptr optMesh_;
00237 cv::Mat optTexture_;
00238 int optRefId_;
00239 rtabmap::Transform * optRefPose_;
00240
00241
00242
00243 Scene main_scene_;
00244
00245 std::list<rtabmap::RtabmapEvent*> rtabmapEvents_;
00246 std::list<rtabmap::RtabmapEvent*> visLocalizationEvents_;
00247 std::list<rtabmap::OdometryEvent> odomEvents_;
00248 std::list<rtabmap::Transform> poseEvents_;
00249
00250 rtabmap::Transform mapToOdom_;
00251
00252 boost::mutex rtabmapMutex_;
00253 boost::mutex visLocalizationMutex_;
00254 boost::mutex meshesMutex_;
00255 boost::mutex odomMutex_;
00256 boost::mutex poseMutex_;
00257 boost::mutex renderingMutex_;
00258
00259 USemaphore screenshotReady_;
00260
00261 std::map<int, Mesh> createdMeshes_;
00262 std::map<int, rtabmap::Transform> rawPoses_;
00263
00264 std::pair<rtabmap::RtabmapEventInit::Status, std::string> status_;
00265
00266 rtabmap::ProgressionStatus progressionStatus_;
00267 };
00268
00269 #endif // TANGO_POINT_CLOUD_POINT_CLOUD_APP_H_