RTABMapApp.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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>  // NOLINT
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 // RTABMapApp handles the application lifecycle and resources.
00049 class RTABMapApp : public UEventsHandler {
00050  public:
00051   // Constructor and deconstructor.
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   // Explicitly reset motion tracking and restart the pipeline.
00064   // Note that this will cause motion tracking to re-initialize.
00065   void TangoResetMotionTracking();
00066 
00067   // Tango Service point cloud callback function for depth data. Called when new
00068   // new point cloud data is available from the Tango Service.
00069   //
00070   // @param pose: The current point cloud returned by the service,
00071   //              caller allocated.
00072   void onPointCloudAvailable(const TangoXYZij* xyz_ij);
00073 
00074   // Tango service pose callback function for pose data. Called when new
00075   // information about device pose is available from the Tango Service.
00076   //
00077   // @param pose: The current pose returned by the service, caller allocated.
00078   void onPoseAvailable(const TangoPoseData* pose);
00079 
00080   // Tango service event callback function for event data. Called when new events
00081   // are available from the Tango Service.
00082   //
00083   // @param event: Tango event, caller allocated.
00084   void onTangoEventAvailable(const TangoEvent* event);
00085 
00086   // Allocate OpenGL resources for rendering, mainly for initializing the Scene.
00087   void InitializeGLContent();
00088 
00089   // Setup the view port width and height.
00090   void SetViewPort(int width, int height);
00091 
00092   // Main render loop.
00093   int Render();
00094 
00095   // Release all non-OpenGL allocated resources.
00096   void onPause();
00097 
00098   // Set render camera's viewing angle, first person, third person or top down.
00099   //
00100   // @param: camera_type, camera type includes first person, third person and
00101   //         top down
00102   void SetCameraType(tango_gl::GestureCamera::CameraType camera_type);
00103 
00104   // Touch event passed from android activity. This function only supports two
00105   // touches.
00106   //
00107   // @param: touch_count, total count for touches.
00108   // @param: event, touch event of current touch.
00109   // @param: x0, normalized touch location for touch 0 on x axis.
00110   // @param: y0, normalized touch location for touch 0 on y axis.
00111   // @param: x1, normalized touch location for touch 1 on x axis.
00112   // @param: y1, normalized touch location for touch 1 on y axis.
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_; // App crashes when loading native library if not dynamic
00240 
00241   // main_scene_ includes all drawable object for visualizing Tango device's
00242   // movement and point cloud.
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_


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:22