RTABMapActivity.java
Go to the documentation of this file.
00001 package com.introlab.rtabmap;
00002 
00003 import java.io.BufferedInputStream;
00004 import java.io.BufferedOutputStream;
00005 import java.io.File;
00006 import java.io.FileInputStream;
00007 import java.io.FileOutputStream;
00008 import java.io.FilenameFilter;
00009 import java.io.IOException;
00010 import java.io.InputStream;
00011 import java.io.OutputStream;
00012 import java.lang.reflect.InvocationTargetException;
00013 import java.lang.reflect.Method;
00014 import java.text.SimpleDateFormat;
00015 import java.util.ArrayList;
00016 import java.util.Arrays;
00017 import java.util.Date;
00018 import java.util.HashMap;
00019 import java.util.List;
00020 import java.util.zip.ZipEntry;
00021 import java.util.zip.ZipOutputStream;
00022 
00023 import android.app.ActionBar;
00024 import android.app.Activity;
00025 import android.app.ActivityManager;
00026 import android.app.ActivityManager.MemoryInfo;
00027 import android.app.AlertDialog;
00028 import android.app.Dialog;
00029 import android.app.Notification;
00030 import android.app.NotificationManager;
00031 import android.app.PendingIntent;
00032 import android.app.ProgressDialog;
00033 import android.content.ComponentName;
00034 import android.content.Context;
00035 import android.content.DialogInterface;
00036 import android.content.DialogInterface.OnShowListener;
00037 import android.content.Intent;
00038 import android.content.ServiceConnection;
00039 import android.content.SharedPreferences;
00040 import android.content.pm.ApplicationInfo;
00041 import android.content.pm.PackageInfo;
00042 import android.content.pm.PackageManager;
00043 import android.content.pm.PackageManager.NameNotFoundException;
00044 import android.content.res.Configuration;
00045 import android.database.Cursor;
00046 import android.database.sqlite.SQLiteDatabase;
00047 import android.graphics.Bitmap;
00048 import android.graphics.Canvas;
00049 import android.graphics.Color;
00050 import android.graphics.Paint;
00051 import android.graphics.Rect;
00052 import android.graphics.Typeface;
00053 import android.hardware.Camera;
00054 import android.hardware.Sensor;
00055 import android.hardware.SensorEvent;
00056 import android.hardware.SensorEventListener;
00057 import android.hardware.SensorManager;
00058 import android.graphics.Point;
00059 import android.hardware.display.DisplayManager;
00060 import android.location.Location;
00061 import android.location.LocationListener;
00062 import android.location.LocationManager;
00063 import android.net.ConnectivityManager;
00064 import android.net.NetworkInfo;
00065 import android.net.Uri;
00066 import android.opengl.GLSurfaceView;
00067 import android.os.AsyncTask;
00068 import android.os.Bundle;
00069 import android.os.Environment;
00070 import android.os.Handler;
00071 import android.os.Debug;
00072 import android.os.IBinder;
00073 import android.os.Message;
00074 import android.preference.ListPreference;
00075 import android.preference.PreferenceManager;
00076 import android.text.Editable;
00077 import android.text.Html;
00078 import android.text.InputType;
00079 import android.text.SpannableString;
00080 import android.text.TextPaint;
00081 import android.text.method.HideReturnsTransformationMethod;
00082 import android.text.method.LinkMovementMethod;
00083 import android.text.util.Linkify;
00084 import android.util.Log;
00085 import android.util.TypedValue;
00086 import android.view.ContextMenu;
00087 import android.view.Display;
00088 import android.view.GestureDetector;
00089 import android.view.Menu;
00090 import android.view.MenuItem;
00091 import android.view.MenuItem.OnMenuItemClickListener;
00092 import android.view.MenuInflater;
00093 import android.view.MotionEvent;
00094 import android.view.Surface;
00095 import android.view.View;
00096 import android.view.ContextMenu.ContextMenuInfo;
00097 import android.view.View.OnClickListener;
00098 import android.view.View.OnCreateContextMenuListener;
00099 import android.view.View.OnTouchListener;
00100 import android.view.Window;
00101 import android.view.WindowManager;
00102 import android.view.inputmethod.EditorInfo;
00103 import android.webkit.WebView;
00104 import android.webkit.WebViewClient;
00105 import android.widget.AdapterView;
00106 import android.widget.AdapterView.OnItemLongClickListener;
00107 import android.widget.AdapterView.OnItemSelectedListener;
00108 import android.widget.ArrayAdapter;
00109 import android.widget.Button;
00110 import android.widget.EditText;
00111 import android.widget.LinearLayout;
00112 import android.widget.ListView;
00113 import android.widget.NumberPicker;
00114 import android.widget.RelativeLayout;
00115 import android.widget.SeekBar;
00116 import android.widget.SeekBar.OnSeekBarChangeListener;
00117 import android.widget.Spinner;
00118 import android.widget.TextView;
00119 import android.widget.Toast;
00120 import android.widget.ToggleButton;
00121 
00122 import com.google.atap.tangoservice.Tango;
00123 
00124 // The main activity of the application. This activity shows debug information
00125 // and a glSurfaceView that renders graphic content.
00126 public class RTABMapActivity extends Activity implements OnClickListener, OnItemSelectedListener, SensorEventListener {
00127 
00128         // Tag for debug logging.
00129         public static final String TAG = RTABMapActivity.class.getSimpleName();
00130         public static boolean DISABLE_LOG = true;
00131 
00132         // The minimum Tango Core version required from this application.
00133         private static final int  MIN_TANGO_CORE_VERSION = 9377;
00134 
00135         // The package name of Tang Core, used for checking minimum Tango Core version.
00136         private static final String TANGO_PACKAGE_NAME = "com.google.tango";
00137 
00138         public static final String EXTRA_KEY_PERMISSIONTYPE = "PERMISSIONTYPE";
00139         public static final String EXTRA_VALUE_ADF = "ADF_LOAD_SAVE_PERMISSION";
00140         
00141         public static final String RTABMAP_TMP_DB = "rtabmap.tmp.db";
00142         public static final String RTABMAP_TMP_DIR = "tmp";
00143         public static final String RTABMAP_TMP_FILENAME = "map";
00144         public static final String RTABMAP_SDCARD_PATH = "/sdcard/";
00145         public static final String RTABMAP_EXPORT_DIR = "Export/";
00146 
00147         public static final String RTABMAP_AUTH_TOKEN_KEY = "com.introlab.rtabmap.AUTH_TOKEN";
00148         public static final String RTABMAP_FILENAME_KEY = "com.introlab.rtabmap.FILENAME";
00149         public static final String RTABMAP_OPENED_DB_PATH_KEY = "com.introlab.rtabmap.OPENED_DB_PATH";
00150         public static final String RTABMAP_WORKING_DIR_KEY = "com.introlab.rtabmap.WORKING_DIR";
00151         public static final int SKETCHFAB_ACTIVITY_CODE = 999;
00152         private String mAuthToken;
00153         
00154         public static final long NOTOUCH_TIMEOUT = 5000; // 5 sec
00155         private boolean mHudVisible = true;
00156         private int mSavedRenderingType = 0;
00157         private boolean mMenuOpened = false;
00158 
00159         // UI states
00160         private static enum State {
00161                 STATE_IDLE,
00162                 STATE_PROCESSING,
00163                 STATE_VISUALIZING,
00164                 STATE_VISUALIZING_WHILE_LOADING
00165         }
00166         State mState = State.STATE_IDLE;
00167 
00168         // GLSurfaceView and renderer, all of the graphic content is rendered
00169         // through OpenGL ES 2.0 in native code.
00170         private Renderer mRenderer = null;
00171         private GLSurfaceView mGLView;
00172         
00173         View mDecorView;
00174         int mStatusBarHeight = 0;
00175         int mActionBarHeight = 0;
00176 
00177         ProgressDialog mProgressDialog;
00178         ProgressDialog mExportProgressDialog;
00179 
00180         // Screen size for normalizing the touch input for orbiting the render camera.
00181         private Point mScreenSize = new Point();
00182         private long mOnPauseStamp = 0;
00183         private boolean mOnPause = false;
00184         private Date mDateOnPause = new Date();
00185         private long mLastFastMovementNotificationStamp = 0;
00186         private boolean mBlockBack = true;
00187         private long mFreeMemoryOnStart = 0;
00188 
00189         private MenuItem mItemSave;
00190         private MenuItem mItemOpen;
00191         private MenuItem mItemPostProcessing;
00192         private MenuItem mItemExport;
00193         private MenuItem mItemSettings;
00194         private MenuItem mItemModes;
00195         private MenuItem mItemReset;
00196         private MenuItem mItemLocalizationMode;
00197         private MenuItem mItemTrajectoryMode;
00198         private MenuItem mItemRenderingPointCloud;
00199         private MenuItem mItemRenderingMesh;
00200         private MenuItem mItemRenderingTextureMesh;
00201         private MenuItem mItemDataRecorderMode;
00202         private MenuItem mItemStatusVisibility;
00203         private MenuItem mItemDebugVisibility;
00204 
00205         private NDSpinner mButtonCameraView;
00206         private ToggleButton mButtonPause;
00207         private ToggleButton mButtonLighting;
00208         private ToggleButton mButtonWireframe;
00209         private ToggleButton mButtonBackfaceShown;
00210         private Button mButtonCloseVisualization;
00211         private Button mButtonSaveOnDevice;
00212         private Button mButtonShareOnSketchfab;
00213         private SeekBar mSeekBarOrthoCut;
00214         private SeekBar mSeekBarGrid;
00215 
00216         private String mOpenedDatabasePath = "";
00217         private String mWorkingDirectory = "";
00218         private String mWorkingDirectoryHuman = "";
00219 
00220         private String mUpdateRate;
00221         private String mTimeThr;
00222         private String mMaxFeatures;
00223         private String mLoopThr;
00224         private String mMinInliers;
00225         private String mMaxOptimizationError;
00226         private boolean mGPSSaved = false;
00227         
00228         private LocationManager mLocationManager;
00229         private LocationListener mLocationListener;
00230         private Location mLastKnownLocation;
00231         private SensorManager mSensorManager;
00232         private float mCompassDeg = 0.0f;
00233 
00234         private int mTotalLoopClosures = 0;
00235         private boolean mMapIsEmpty = false;
00236         int mMapNodes = 0;
00237 
00238         private Toast mToast = null;
00239         
00240         private AlertDialog mMemoryWarningDialog = null;
00241         
00242         private final int STATUS_TEXTS_SIZE = 19;
00243         private final int STATUS_TEXTS_POSE_INDEX = 5;
00244         private String[] mStatusTexts = new String[STATUS_TEXTS_SIZE];
00245         
00246         GestureDetector mGesDetect = null;
00247 
00248         //Tango Service connection.
00249         ServiceConnection mTangoServiceConnection = new ServiceConnection() {
00250                 public void onServiceConnected(ComponentName name, final IBinder service) {
00251                         Thread bindThread = new Thread(new Runnable() {
00252                                 public void run() {
00253                                         if(!RTABMapLib.onTangoServiceConnected(service))
00254                                         {
00255                                                 runOnUiThread(new Runnable() {
00256                                                         public void run() {
00257                                                                 mToast.makeText(getApplicationContext(), 
00258                                                                                 String.format("Failed to intialize Tango!"), mToast.LENGTH_LONG).show();
00259                                                         } 
00260                                                 });
00261                                         }
00262                                 }
00263                         });
00264                         bindThread.start();
00265                 }
00266 
00267                 public void onServiceDisconnected(ComponentName name) {
00268                         // Handle this if you need to gracefully shutdown/retry
00269                         // in the event that Tango itself crashes/gets upgraded while running.
00270                         mToast.makeText(getApplicationContext(), 
00271                                         String.format("Tango disconnected!"), mToast.LENGTH_LONG).show();
00272                 }
00273         };
00274 
00275         @Override
00276         protected void onCreate(Bundle savedInstanceState) {
00277                 super.onCreate(savedInstanceState);
00278                 setTitle(R.string.menu_name);
00279                 
00280                 mFreeMemoryOnStart = getFreeMemory();
00281 
00282                 // Query screen size, the screen size is used for computing the normalized
00283                 // touch point.
00284                 Display display = getWindowManager().getDefaultDisplay();
00285                 display.getSize(mScreenSize);
00286 
00287                 getWindow().addFlags(WindowManager.LayoutParams.FLAG_KEEP_SCREEN_ON);
00288                 getWindow().addFlags(WindowManager.LayoutParams.FLAG_TRANSLUCENT_STATUS);
00289                 
00290                 // Setting content view of this activity.
00291                 setContentView(R.layout.activity_rtabmap);
00292                 
00293                 // Make sure to initialize all default values
00294                 SettingsActivity settings;
00295                 
00296                 mDecorView = getWindow().getDecorView();
00297                 mStatusBarHeight = getStatusBarHeight();
00298                 mActionBarHeight = getActionBarHeight();
00299         
00300                 // Buttons for selecting camera view and Set up button click listeners.
00301                 mButtonCameraView = (NDSpinner)findViewById(R.id.camera_button);
00302                 mButtonPause = (ToggleButton)findViewById(R.id.pause_button);
00303                 mButtonLighting = (ToggleButton)findViewById(R.id.light_button);
00304                 mButtonWireframe = (ToggleButton)findViewById(R.id.wireframe_button);
00305                 mButtonBackfaceShown = (ToggleButton)findViewById(R.id.backface_button);
00306                 mButtonCloseVisualization = (Button)findViewById(R.id.close_visualization_button);
00307                 mButtonSaveOnDevice = (Button)findViewById(R.id.button_saveOnDevice);
00308                 mButtonShareOnSketchfab = (Button)findViewById(R.id.button_shareToSketchfab);
00309                 mButtonCameraView.setOnItemSelectedListener(this);
00310                 mButtonPause.setOnClickListener(this);
00311                 mButtonLighting.setOnClickListener(this);
00312                 mButtonWireframe.setOnClickListener(this);
00313                 mButtonBackfaceShown.setOnClickListener(this);
00314                 mButtonCloseVisualization.setOnClickListener(this);
00315                 mButtonSaveOnDevice.setOnClickListener(this);
00316                 mButtonShareOnSketchfab.setOnClickListener(this);
00317                 mButtonLighting.setChecked(false);
00318                 mButtonLighting.setVisibility(View.INVISIBLE);
00319                 mButtonWireframe.setChecked(false);
00320                 mButtonWireframe.setVisibility(View.INVISIBLE);
00321                 mButtonCloseVisualization.setVisibility(View.INVISIBLE);
00322                 mButtonSaveOnDevice.setVisibility(View.INVISIBLE);
00323                 mButtonShareOnSketchfab.setVisibility(View.INVISIBLE);
00324                 if(mItemRenderingMesh != null && mItemRenderingTextureMesh != null)
00325                 {
00326                         mButtonBackfaceShown.setVisibility(mItemRenderingMesh.isChecked() || mItemRenderingTextureMesh.isChecked()?View.VISIBLE:View.INVISIBLE);
00327                 }
00328                 
00329                 ArrayAdapter<CharSequence> adapter = ArrayAdapter.createFromResource(this, R.array.camera_view_array, android.R.layout.simple_spinner_item);
00330                 adapter.setDropDownViewResource(android.R.layout.simple_spinner_dropdown_item);
00331                 mButtonCameraView.setAdapter(adapter);
00332                 mButtonCameraView.setOnTouchListener(new OnTouchListener() {
00333                     @Override
00334                     public boolean onTouch(View v, MotionEvent event) {
00335                         resetNoTouchTimer();
00336                         return false;
00337                     }
00338                 });
00339                 
00340                 mSeekBarOrthoCut = (SeekBar)findViewById(R.id.seekBar_ortho_cut);
00341                 mSeekBarOrthoCut.setMax(120);
00342                 mSeekBarOrthoCut.setProgress(80);
00343                 mSeekBarOrthoCut.setOnSeekBarChangeListener(new OnSeekBarChangeListener() {
00344                           @Override
00345                           public void onProgressChanged(SeekBar seekBar, int progressValue, boolean fromUser) {
00346                                   RTABMapLib.setOrthoCropFactor((float)(120-progressValue)/20.0f - 3.0f);
00347                                   resetNoTouchTimer();
00348                           }
00349                         
00350                           @Override
00351                           public void onStartTrackingTouch(SeekBar seekBar) {
00352                           }
00353                         
00354                           @Override
00355                           public void onStopTrackingTouch(SeekBar seekBar) {
00356                           }
00357                    });
00358                 
00359                 mSeekBarGrid = (SeekBar)findViewById(R.id.seekBar_grid);
00360                 mSeekBarGrid.setMax(180);
00361                 mSeekBarGrid.setProgress(90);
00362                 mSeekBarGrid.setOnSeekBarChangeListener(new OnSeekBarChangeListener() {
00363                           @Override
00364                           public void onProgressChanged(SeekBar seekBar, int progressValue, boolean fromUser) {
00365                                   RTABMapLib.setGridRotation(((float)progressValue-90.0f)/2.0f);
00366                                   resetNoTouchTimer();
00367                           }
00368                         
00369                           @Override
00370                           public void onStartTrackingTouch(SeekBar seekBar) {
00371                           }
00372                         
00373                           @Override
00374                           public void onStopTrackingTouch(SeekBar seekBar) {
00375                           }
00376                    });
00377 
00378                 mToast = Toast.makeText(getApplicationContext(), "", Toast.LENGTH_SHORT);
00379 
00380                 // OpenGL view where all of the graphics are drawn.
00381                 mGLView = (GLSurfaceView) findViewById(R.id.gl_surface_view);
00382 
00383                 mGesDetect = new GestureDetector(this, new DoubleTapGestureDetector());
00384                 
00385                 // Configure OpenGL renderer
00386                 mGLView.setEGLContextClientVersion(2);
00387                 mGLView.setEGLConfigChooser(8, 8, 8, 8, 24, 0);
00388                 mGLView.setOnTouchListener(new OnTouchListener() {
00389                 @Override
00390                 public boolean onTouch(View v, MotionEvent event) {
00391                         
00392                         resetNoTouchTimer(getActionBar().isShowing() && mHudVisible == false);
00393                         
00394                     mGesDetect.onTouchEvent(event);
00395                     
00396                     // Pass the touch event to the native layer for camera control.
00397                         // Single touch to rotate the camera around the device.
00398                         // Two fingers to zoom in and out.
00399                         int pointCount = event.getPointerCount();
00400                         if (pointCount == 1) {
00401                                 float normalizedX = event.getX(0) / mScreenSize.x;
00402                                 float normalizedY = event.getY(0) / mScreenSize.y;
00403                                 RTABMapLib.onTouchEvent(1, 
00404                                                 event.getActionMasked(), normalizedX, normalizedY, 0.0f, 0.0f);
00405                         }
00406                         if (pointCount == 2) {
00407                                 if (event.getActionMasked() == MotionEvent.ACTION_POINTER_UP) {
00408                                         int index = event.getActionIndex() == 0 ? 1 : 0;
00409                                         float normalizedX = event.getX(index) / mScreenSize.x;
00410                                         float normalizedY = event.getY(index) / mScreenSize.y;
00411                                         RTABMapLib.onTouchEvent(1, 
00412                                                         MotionEvent.ACTION_DOWN, normalizedX, normalizedY, 0.0f, 0.0f);
00413                                 } else {
00414                                         float normalizedX0 = event.getX(0) / mScreenSize.x;
00415                                         float normalizedY0 = event.getY(0) / mScreenSize.y;
00416                                         float normalizedX1 = event.getX(1) / mScreenSize.x;
00417                                         float normalizedY1 = event.getY(1) / mScreenSize.y;
00418                                         RTABMapLib.onTouchEvent(2, event.getActionMasked(),
00419                                                         normalizedX0, normalizedY0, normalizedX1, normalizedY1);
00420                                 }
00421                         }
00422                         return true;
00423                 }
00424             });
00425                 
00426                 // Configure the OpenGL renderer.
00427                 mRenderer = new Renderer(this);
00428                 mGLView.setRenderer(mRenderer);
00429 
00430                 mProgressDialog = new ProgressDialog(this);
00431                 mProgressDialog.setCanceledOnTouchOutside(false);
00432                 mRenderer.setProgressDialog(mProgressDialog);
00433                 mRenderer.setToast(mToast);
00434                 setNavVisibility(true);
00435                 
00436                 mExportProgressDialog = new ProgressDialog(this);
00437                 mExportProgressDialog.setCanceledOnTouchOutside(false);
00438                 mExportProgressDialog.setCancelable(false);
00439                 mExportProgressDialog.setProgressStyle(ProgressDialog.STYLE_HORIZONTAL);
00440                 mExportProgressDialog.setProgressNumberFormat(null);
00441                 mExportProgressDialog.setProgressPercentFormat(null);
00442                 mExportProgressDialog.setButton(DialogInterface.BUTTON_NEGATIVE, "Cancel", new DialogInterface.OnClickListener() {
00443                     @Override
00444                     public void onClick(DialogInterface dialog, int which) {
00445                         RTABMapLib.cancelProcessing();
00446                         
00447                         mProgressDialog.setTitle("");
00448                         mProgressDialog.setMessage(String.format("Cancelling..."));
00449                         mProgressDialog.show();
00450                     }
00451                 });
00452 
00453                 // Check if the Tango Core is out dated.
00454                 if (!CheckTangoCoreVersion(MIN_TANGO_CORE_VERSION)) {
00455                         mToast.makeText(this, "Tango Core out dated, please update in Play Store", mToast.LENGTH_LONG).show();
00456                         finish();
00457                         return;
00458                 }   
00459 
00460                 mOpenedDatabasePath = "";
00461                 mWorkingDirectory = "";
00462                 mWorkingDirectoryHuman = "";
00463                 mTotalLoopClosures = 0;
00464                 mLastFastMovementNotificationStamp = System.currentTimeMillis()/1000;
00465 
00466                 if(Environment.getExternalStorageState().compareTo(Environment.MEDIA_MOUNTED)==0)
00467                 {
00468                         File extStore = Environment.getExternalStorageDirectory();
00469                         mWorkingDirectory = extStore.getAbsolutePath() + "/" + getString(R.string.app_name) + "/";
00470                         extStore = new File(mWorkingDirectory);
00471                         extStore.mkdirs();
00472                         mWorkingDirectoryHuman = RTABMAP_SDCARD_PATH + getString(R.string.app_name) + "/";
00473                 }
00474                 else
00475                 {
00476                         // show warning that data cannot be saved!
00477                         mToast.makeText(getApplicationContext(), 
00478                                         String.format("Failed to get external storage path (SD-CARD, state=%s). Saving disabled.", 
00479                                                         Environment.getExternalStorageState()), mToast.LENGTH_LONG).show();
00480                 }
00481 
00482                 RTABMapLib.onCreate(this);
00483                 String tmpDatabase = mWorkingDirectory+RTABMAP_TMP_DB;
00484                 (new File(tmpDatabase)).delete();
00485                 SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(this);
00486                 boolean databaseInMemory = sharedPref.getBoolean(getString(R.string.pref_key_db_in_memory), Boolean.parseBoolean(getString(R.string.pref_default_db_in_memory)));
00487                 RTABMapLib.openDatabase(tmpDatabase, databaseInMemory, false);
00488 
00489                 DisplayManager displayManager = (DisplayManager) getSystemService(DISPLAY_SERVICE);
00490                 if (displayManager != null) {
00491                         displayManager.registerDisplayListener(new DisplayManager.DisplayListener() {
00492                                 @Override
00493                                 public void onDisplayAdded(int displayId) {
00494 
00495                                 }
00496 
00497                                 @Override
00498                                 public void onDisplayChanged(int displayId) {
00499                                         synchronized (this) {
00500                                                 setAndroidOrientation();
00501                                                 Display display = getWindowManager().getDefaultDisplay();
00502                                                 display.getSize(mScreenSize);
00503                                         }
00504                                 }
00505 
00506                                 @Override
00507                                 public void onDisplayRemoved(int displayId) {}
00508                         }, null);
00509                 }
00510 
00511                 // Acquire a reference to the system Location Manager
00512                 mLocationManager = (LocationManager) this.getSystemService(Context.LOCATION_SERVICE);
00513 
00514                 // Define a listener that responds to location updates
00515                 mLocationListener = new LocationListener() {
00516                         public void onLocationChanged(Location location) {
00517                                 mLastKnownLocation = location;
00518                                 double stamp = location.getTime()/1000.0;
00519                                 if(!DISABLE_LOG) Log.d(TAG, String.format("GPS received at %f (%d)", stamp, location.getTime()));
00520                                 RTABMapLib.setGPS(
00521                                                 stamp,
00522                                                 (double)location.getLongitude(), 
00523                                                 (double)location.getLatitude(), 
00524                                                 (double)location.getAltitude(),  
00525                                                 (double)location.getAccuracy(),
00526                                                 (double)mCompassDeg);
00527                         }
00528 
00529                         public void onStatusChanged(String provider, int status, Bundle extras) {}
00530 
00531                         public void onProviderEnabled(String provider) {}
00532 
00533                         public void onProviderDisabled(String provider) {}
00534                 };
00535 
00536                 mSensorManager = (SensorManager) getSystemService(SENSOR_SERVICE);
00537 
00538                 DISABLE_LOG =  !( 0 != ( getApplicationInfo().flags & ApplicationInfo.FLAG_DEBUGGABLE ) );
00539         }
00540 
00541         @Override
00542         public void onSensorChanged(SensorEvent event) {
00543                 // get the angle around the z-axis rotated
00544                 mCompassDeg = event.values[0];
00545         }
00546 
00547         @Override
00548         public void onAccuracyChanged(Sensor sensor, int accuracy) {
00549                 // not in use
00550         }
00551 
00552 
00553         public int getStatusBarHeight() {
00554                 int result = 0;
00555                 int resourceId = getResources().getIdentifier("status_bar_height", "dimen", "android");
00556                 if (resourceId > 0) {
00557                         result = getResources().getDimensionPixelSize(resourceId);
00558                 }
00559                 return result;
00560         }
00561         public int getActionBarHeight() {
00562                 int result = 0;
00563                 TypedValue tv = new TypedValue();
00564                 if (getTheme().resolveAttribute(android.R.attr.actionBarSize, tv, true))
00565                 {
00566                         result = TypedValue.complexToDimensionPixelSize(tv.data,getResources().getDisplayMetrics());
00567                 }
00568 
00569                 return result;
00570         }
00571         
00572         @Override
00573         public void onWindowFocusChanged(boolean hasFocus) {
00574 
00575                 super.onWindowFocusChanged(hasFocus);
00576 
00577                 if(!mHudVisible)
00578                 {
00579                         mRenderer.setOffset(!hasFocus?-mStatusBarHeight:0);
00580                 }
00581         }
00582                 
00583         // This snippet hides the system bars.
00584         private void setNavVisibility(boolean visible) {
00585                 int newVis = View.SYSTEM_UI_FLAG_LAYOUT_FULLSCREEN
00586                 | View.SYSTEM_UI_FLAG_LAYOUT_HIDE_NAVIGATION
00587                 | View.SYSTEM_UI_FLAG_LAYOUT_STABLE;
00588         if (!visible) {
00589             newVis |= View.SYSTEM_UI_FLAG_LOW_PROFILE 
00590                         | View.SYSTEM_UI_FLAG_FULLSCREEN       // hide status bar
00591                     | View.SYSTEM_UI_FLAG_HIDE_NAVIGATION  // hide nav bar
00592                     | View.SYSTEM_UI_FLAG_IMMERSIVE; 
00593             mRenderer.setOffset(!hasWindowFocus()?-mStatusBarHeight:0);
00594         }
00595         else
00596         {
00597                 mRenderer.setOffset(-mStatusBarHeight-mActionBarHeight);
00598         }
00599 
00600         // Set the new desired visibility.
00601         mDecorView.setSystemUiVisibility(newVis);
00602         }
00603 
00604         @Override
00605         protected void onActivityResult(int requestCode, int resultCode, Intent data) {
00606                 // Check which request we're responding to
00607                 if (requestCode == Tango.TANGO_INTENT_ACTIVITYCODE) {
00608                         // Make sure the request was successful
00609                         if (resultCode == RESULT_CANCELED) {
00610                                 mToast.makeText(this, "Motion Tracking Permissions Required!", mToast.LENGTH_SHORT).show();
00611                                 finish();
00612                         }
00613                 }
00614                 else if (requestCode == SKETCHFAB_ACTIVITY_CODE) {
00615                         // Make sure the request was successful
00616                         if (resultCode == RESULT_OK) {
00617                                 mAuthToken = data.getStringExtra(RTABMAP_AUTH_TOKEN_KEY);
00618                         }
00619                 }
00620         }
00621         
00622         @Override
00623         public boolean onMenuOpened(int featureId, Menu menu) {
00624                 mMenuOpened = true;
00625             return super.onMenuOpened(featureId, menu);
00626         }
00627 
00628         @Override
00629         public void onPanelClosed(int featureId, Menu menu) {
00630                 mMenuOpened = false;
00631         }
00632         
00633         @Override
00634         public void onBackPressed() {
00635            
00636                 if(mBlockBack)
00637                 {
00638                         mToast.makeText(this, "Press Back once more to exit", mToast.LENGTH_LONG).show();
00639                         mBlockBack = false;
00640                 }
00641                 else
00642                 {
00643                         super.onBackPressed();
00644                 }
00645         }
00646         
00647         @Override
00648         protected void onPause() {
00649                 super.onPause();
00650                 stopDisconnectTimer();
00651                 
00652                 if(!DISABLE_LOG) Log.i(TAG, "onPause()");
00653                 mOnPause = true;
00654                 
00655                 if(!mButtonPause.isChecked())
00656                 {
00657                         mButtonPause.setChecked(true);
00658                         pauseMapping();
00659                 }
00660                 
00661                 mLocationManager.removeUpdates(mLocationListener);
00662                 mSensorManager.unregisterListener(this);
00663 
00664                 RTABMapLib.onPause();
00665                 
00666                 unbindService(mTangoServiceConnection);
00667                 
00668                 // This deletes OpenGL context!
00669                 mGLView.onPause();
00670                 
00671                 mOnPauseStamp = System.currentTimeMillis()/1000;
00672         }
00673 
00674         @Override
00675         protected void onResume() {
00676                 super.onResume();
00677                 
00678                 mProgressDialog.setTitle("");
00679                 if(mOnPause)
00680                 {
00681                         if(System.currentTimeMillis()/1000 - mOnPauseStamp < 1)
00682                         {
00683                                 mProgressDialog.setMessage(String.format("RTAB-Map has been interrupted by another application, Tango should be re-initialized! Set your phone/tablet in Airplane mode if this happens often."));
00684                         }
00685                         else
00686                         {
00687                                 mProgressDialog.setMessage(String.format("Hold Tight! Initializing Tango Service..."));
00688                         }
00689                         mToast.makeText(this, "Mapping is paused!", mToast.LENGTH_LONG).show();
00690                 }
00691                 else
00692                 {
00693                         mProgressDialog.setMessage(String.format("Hold Tight! Initializing Tango Service...\nTip: If the camera is still drifting just after the mapping has started, do \"Reset\"."));
00694                 }
00695                 mProgressDialog.show();
00696                 mOnPause = false;
00697                 setAndroidOrientation();
00698                 
00699                 // update preferences
00700                 try
00701                 {
00702                         if(!DISABLE_LOG) Log.d(TAG, "update preferences...");
00703                         SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(this);
00704                         mUpdateRate = sharedPref.getString(getString(R.string.pref_key_update_rate), getString(R.string.pref_default_update_rate));
00705                         String maxSpeed = sharedPref.getString(getString(R.string.pref_key_max_speed), getString(R.string.pref_default_max_speed));
00706                         mTimeThr = sharedPref.getString(getString(R.string.pref_key_time_thr), getString(R.string.pref_default_time_thr));
00707                         String memThr = sharedPref.getString(getString(R.string.pref_key_mem_thr), getString(R.string.pref_default_mem_thr));
00708                         mLoopThr = sharedPref.getString(getString(R.string.pref_key_loop_thr), getString(R.string.pref_default_loop_thr));
00709                         String simThr = sharedPref.getString(getString(R.string.pref_key_sim_thr), getString(R.string.pref_default_sim_thr));
00710                         mMinInliers = sharedPref.getString(getString(R.string.pref_key_min_inliers), getString(R.string.pref_default_min_inliers));
00711                         mMaxOptimizationError = sharedPref.getString(getString(R.string.pref_key_opt_error), getString(R.string.pref_default_opt_error));
00712                         float maxOptimizationError = Float.parseFloat(mMaxOptimizationError);
00713                         if(maxOptimizationError >0 && maxOptimizationError<1) 
00714                         {
00715                                 Log.w(TAG, "Migration of " + getString(R.string.pref_key_opt_error) + " from " + mMaxOptimizationError + " to " + getString(R.string.pref_default_opt_error)) ;
00716                                 SharedPreferences.Editor editor = sharedPref.edit();
00717                                 editor.putString(getString(R.string.pref_key_opt_error), getString(R.string.pref_default_opt_error));
00718                                 editor.commit();
00719                                 mMaxOptimizationError = getString(R.string.pref_default_opt_error);
00720                         }
00721                         mMaxFeatures = sharedPref.getString(getString(R.string.pref_key_features_voc), getString(R.string.pref_default_features_voc));
00722                         String maxFeaturesLoop = sharedPref.getString(getString(R.string.pref_key_features), getString(R.string.pref_default_features));
00723                         String featureType = sharedPref.getString(getString(R.string.pref_key_features_type), getString(R.string.pref_default_features_type));
00724                         boolean keepAllDb = sharedPref.getBoolean(getString(R.string.pref_key_keep_all_db), Boolean.parseBoolean(getString(R.string.pref_default_keep_all_db)));
00725                         boolean optimizeFromGraphEnd = sharedPref.getBoolean(getString(R.string.pref_key_optimize_end), Boolean.parseBoolean(getString(R.string.pref_default_optimize_end)));
00726                         String optimizer = sharedPref.getString(getString(R.string.pref_key_optimizer), getString(R.string.pref_default_optimizer));
00727                         mGPSSaved = sharedPref.getBoolean(getString(R.string.pref_key_gps_saved), Boolean.parseBoolean(getString(R.string.pref_default_gps_saved)));
00728                         if(mGPSSaved)
00729                         {
00730                                 mLocationManager.requestLocationUpdates(LocationManager.GPS_PROVIDER, 0, 0, mLocationListener);
00731                                 mSensorManager.registerListener(this, mSensorManager.getDefaultSensor(Sensor.TYPE_ORIENTATION), SensorManager.SENSOR_DELAY_GAME);
00732                         }
00733                         
00734                         if(!DISABLE_LOG) Log.d(TAG, "set mapping parameters");
00735                         RTABMapLib.setOnlineBlending(sharedPref.getBoolean(getString(R.string.pref_key_blending), Boolean.parseBoolean(getString(R.string.pref_default_blending))));
00736                         RTABMapLib.setNodesFiltering(sharedPref.getBoolean(getString(R.string.pref_key_nodes_filtering), Boolean.parseBoolean(getString(R.string.pref_default_nodes_filtering))));
00737                         RTABMapLib.setRawScanSaved(sharedPref.getBoolean(getString(R.string.pref_key_raw_scan_saved), Boolean.parseBoolean(getString(R.string.pref_default_raw_scan_saved))));
00738                         RTABMapLib.setFullResolution(sharedPref.getBoolean(getString(R.string.pref_key_resolution), Boolean.parseBoolean(getString(R.string.pref_default_resolution))));
00739                         RTABMapLib.setSmoothing(sharedPref.getBoolean(getString(R.string.pref_key_smoothing), Boolean.parseBoolean(getString(R.string.pref_default_smoothing))));
00740                         RTABMapLib.setCameraColor(!sharedPref.getBoolean(getString(R.string.pref_key_fisheye), Boolean.parseBoolean(getString(R.string.pref_default_fisheye))));
00741                         RTABMapLib.setAppendMode(sharedPref.getBoolean(getString(R.string.pref_key_append), Boolean.parseBoolean(getString(R.string.pref_default_append))));
00742                         RTABMapLib.setMappingParameter("Rtabmap/DetectionRate", mUpdateRate);
00743                         RTABMapLib.setMappingParameter("Rtabmap/TimeThr", mTimeThr);
00744                         RTABMapLib.setMappingParameter("Rtabmap/MemoryThr", memThr);
00745                         RTABMapLib.setMappingParameter("RGBD/LinearSpeedUpdate", maxSpeed);
00746                         RTABMapLib.setMappingParameter("RGBD/AngularSpeedUpdate", String.valueOf(Float.parseFloat(maxSpeed)/2.0f));
00747                         RTABMapLib.setMappingParameter("Mem/RehearsalSimilarity", simThr);
00748                         RTABMapLib.setMappingParameter("Kp/MaxFeatures", mMaxFeatures);
00749                         RTABMapLib.setMappingParameter("Vis/MaxFeatures", maxFeaturesLoop);
00750                         RTABMapLib.setMappingParameter("Vis/MinInliers", mMinInliers);
00751                         RTABMapLib.setMappingParameter("Rtabmap/LoopThr", mLoopThr);
00752                         RTABMapLib.setMappingParameter("RGBD/OptimizeMaxError", mMaxOptimizationError);
00753                         RTABMapLib.setMappingParameter("Kp/DetectorStrategy", featureType);
00754                         RTABMapLib.setMappingParameter("Vis/FeatureType", featureType);
00755                         RTABMapLib.setMappingParameter("Mem/NotLinkedNodesKept", String.valueOf(keepAllDb));
00756                         RTABMapLib.setMappingParameter("RGBD/OptimizeFromGraphEnd", String.valueOf(optimizeFromGraphEnd));
00757                         RTABMapLib.setMappingParameter("Optimizer/Strategy", optimizer);
00758         
00759                         if(!DISABLE_LOG) Log.d(TAG, "set exporting parameters...");
00760                         RTABMapLib.setCloudDensityLevel(Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_density), getString(R.string.pref_default_density))));
00761                         RTABMapLib.setMaxCloudDepth(Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_depth), getString(R.string.pref_default_depth))));
00762                         RTABMapLib.setMinCloudDepth(Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_min_depth), getString(R.string.pref_default_min_depth))));
00763                         RTABMapLib.setPointSize(Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_point_size), getString(R.string.pref_default_point_size))));
00764                         RTABMapLib.setMeshAngleTolerance(Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_angle), getString(R.string.pref_default_angle))));
00765                         RTABMapLib.setMeshTriangleSize(Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_triangle), getString(R.string.pref_default_triangle))));
00766                         float bgColor = Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_background_color), getString(R.string.pref_default_background_color)));
00767                         RTABMapLib.setBackgroundColor(bgColor);
00768                         mRenderer.setTextColor(bgColor>=0.6f?0.0f:1.0f);
00769                         
00770                         if(!DISABLE_LOG) Log.d(TAG, "set rendering parameters...");
00771                         RTABMapLib.setClusterRatio(Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_cluster_ratio), getString(R.string.pref_default_cluster_ratio))));
00772                         RTABMapLib.setMaxGainRadius(Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_gain_max_radius), getString(R.string.pref_default_gain_max_radius))));
00773                         RTABMapLib.setRenderingTextureDecimation(Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_rendering_texture_decimation), getString(R.string.pref_default_rendering_texture_decimation))));
00774         
00775                         if(mItemRenderingPointCloud != null)
00776                         {
00777                                 int renderingType =  sharedPref.getInt(getString(R.string.pref_key_rendering), Integer.parseInt(getString(R.string.pref_default_rendering)));
00778                                 if(renderingType == 0)
00779                                 {
00780                                         mItemRenderingPointCloud.setChecked(true);
00781                                 }
00782                                 else if(renderingType == 1)
00783                                 {
00784                                         mItemRenderingMesh.setChecked(true);
00785                                 }
00786                                 else
00787                                 {
00788                                         mItemRenderingTextureMesh.setChecked(true);
00789                                 }
00790                                 RTABMapLib.setMeshRendering(
00791                                                 mItemRenderingMesh.isChecked() || mItemRenderingTextureMesh.isChecked(), 
00792                                                 mItemRenderingTextureMesh.isChecked());
00793                                 
00794                                 mButtonBackfaceShown.setVisibility(mItemRenderingMesh.isChecked() || mItemRenderingTextureMesh.isChecked()?View.VISIBLE:View.INVISIBLE);
00795                         }
00796                 }
00797                 catch(Exception e)
00798                 {
00799                         Log.e(TAG, "Error parsing preferences: " + e.getMessage());
00800                         mToast.makeText(this, String.format("Error parsing preferences: "+e.getMessage()), mToast.LENGTH_LONG).show();
00801                 }
00802 
00803                 if(!DISABLE_LOG) Log.i(TAG, String.format("onResume()"));
00804 
00805                 if (Tango.hasPermission(this, Tango.PERMISSIONTYPE_MOTION_TRACKING)) {
00806 
00807                         mGLView.onResume();
00808 
00809                 } else {
00810                         if(!DISABLE_LOG) Log.i(TAG, String.format("Asking for motion tracking permission"));
00811                         startActivityForResult(
00812                                         Tango.getRequestPermissionIntent(Tango.PERMISSIONTYPE_MOTION_TRACKING),
00813                                         Tango.TANGO_INTENT_ACTIVITYCODE);
00814                 }
00815                 
00816                 TangoInitializationHelper.bindTangoService(getActivity(), mTangoServiceConnection);
00817                 resetNoTouchTimer(true);
00818         }
00819         
00820         private void setCamera(int type)
00821         {                       
00822                 if(!DISABLE_LOG) Log.i(TAG, String.format("called setCamera(type=%d);", type));
00823                 
00824                 // for convenience, for a refresh of the memory used
00825                 long freeMemory = getFreeMemory();
00826                 mStatusTexts[1] = getString(R.string.memory)+String.valueOf(mFreeMemoryOnStart>freeMemory?mFreeMemoryOnStart-freeMemory:0);
00827                 mStatusTexts[2] = getString(R.string.free_memory)+String.valueOf(freeMemory);
00828                 updateStatusTexts();
00829                                 
00830                 RTABMapLib.setCamera(type);
00831                 mButtonCameraView.setSelection(type, true);
00832                 mSeekBarOrthoCut.setVisibility(type!=3?View.INVISIBLE:View.VISIBLE);
00833                 mSeekBarGrid.setVisibility(mSeekBarGrid.isEnabled() && type==3?View.VISIBLE:View.INVISIBLE);
00834                 if(type==3)
00835                 {
00836                         mSeekBarOrthoCut.setMax(120);
00837                         mSeekBarOrthoCut.setProgress(80);
00838                 }
00839         }
00840 
00841         @Override
00842         public void onClick(View v) {
00843                 // Handle button clicks.
00844                 switch (v.getId()) {
00845                 case R.id.gl_surface_view:
00846 
00847                         break;
00848                 case R.id.pause_button:
00849                         pauseMapping();
00850                         break;
00851                 case R.id.light_button:
00852                         RTABMapLib.setLighting(mButtonLighting.isChecked());
00853                         break;
00854                 case R.id.backface_button:
00855                         RTABMapLib.setBackfaceCulling(!mButtonBackfaceShown.isChecked());
00856                         break;
00857                 case R.id.wireframe_button:
00858                         RTABMapLib.setWireframe(mButtonWireframe.isChecked());
00859                         break;
00860                 case R.id.close_visualization_button:
00861                         if(mSavedRenderingType==0)
00862                         {
00863                                 mItemRenderingPointCloud.setChecked(true);
00864                         }
00865                         else if(mSavedRenderingType==1)
00866                         {
00867                                 mItemRenderingMesh.setChecked(true);
00868                         }
00869                         else 
00870                         {
00871                                 mItemRenderingTextureMesh.setChecked(true);
00872                         }
00873                         updateState(State.STATE_IDLE);
00874                         RTABMapLib.postExportation(false);
00875                         break;
00876                 case R.id.button_saveOnDevice:
00877                         saveOnDevice();
00878                         break;
00879                 case R.id.button_shareToSketchfab:
00880                         shareToSketchfab();
00881                         break;
00882                 default:
00883                         return;
00884                 }
00885                 resetNoTouchTimer();
00886         }
00887         
00888         public void onItemSelected(AdapterView<?> parent, View view, int pos, long id) {
00889                 setCamera(pos);
00890                 resetNoTouchTimer();
00891     }
00892 
00893     public void onNothingSelected(AdapterView<?> parent) {
00894         resetNoTouchTimer();
00895     }
00896                 
00897         private void setAndroidOrientation() {
00898         Display display = getWindowManager().getDefaultDisplay();
00899         Camera.CameraInfo colorCameraInfo = new Camera.CameraInfo();
00900         SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(this);
00901         boolean fisheye = sharedPref.getBoolean(getString(R.string.pref_key_fisheye), Boolean.parseBoolean(getString(R.string.pref_default_fisheye)));
00902         Camera.getCameraInfo(fisheye?1:0, colorCameraInfo);
00903         RTABMapLib.setScreenRotation(display.getRotation(), colorCameraInfo.orientation);
00904     }
00905         
00906         class DoubleTapGestureDetector extends GestureDetector.SimpleOnGestureListener {
00907 
00908         @Override
00909         public boolean onDoubleTap(MotionEvent event) {
00910                 if(!DISABLE_LOG) Log.i(TAG, "onDoubleTap");
00911                 float normalizedX = event.getX(0) / mScreenSize.x;
00912                         float normalizedY = event.getY(0) / mScreenSize.y;
00913                 RTABMapLib.onTouchEvent(3, event.getActionMasked(), normalizedX, normalizedY, 0.0f, 0.0f);
00914             return true;
00915         }
00916         @Override
00917         public boolean onSingleTapConfirmed(MotionEvent event) {
00918                 if(!DISABLE_LOG) Log.i(TAG, "onSingleTapConfirmed");
00919                 if(mHudVisible)
00920                         {
00921                                 notouchHandler.removeCallbacks(notouchCallback);
00922                                 notouchHandler.postDelayed(notouchCallback, 0);
00923                         }
00924                         else
00925                         {
00926                                 resetNoTouchTimer(true);
00927                         }
00928             return true;
00929         }
00930     }
00931 
00932         @Override
00933         public boolean onCreateOptionsMenu(Menu menu) {
00934                 if(!DISABLE_LOG) Log.i(TAG, "called onCreateOptionsMenu;");
00935 
00936                 MenuInflater inflater = getMenuInflater();
00937                 inflater.inflate(R.menu.optionmenu, menu);
00938                 
00939                 getActionBar().setDisplayShowHomeEnabled(true);
00940                 getActionBar().setIcon(R.drawable.ic_launcher);
00941 
00942                 mItemSave = menu.findItem(R.id.save);
00943                 mItemOpen = menu.findItem(R.id.open);
00944                 mItemPostProcessing = menu.findItem(R.id.post_processing);
00945                 mItemExport = menu.findItem(R.id.export);
00946                 mItemSettings = menu.findItem(R.id.settings);
00947                 mItemModes = menu.findItem(R.id.modes);
00948                 mItemReset = menu.findItem(R.id.reset);
00949                 mItemLocalizationMode = menu.findItem(R.id.localization_mode);
00950                 mItemTrajectoryMode = menu.findItem(R.id.trajectory_mode);
00951                 mItemRenderingPointCloud = menu.findItem(R.id.point_cloud);
00952                 mItemRenderingMesh = menu.findItem(R.id.mesh);
00953                 mItemRenderingTextureMesh = menu.findItem(R.id.texture_mesh);
00954                 mItemDataRecorderMode = menu.findItem(R.id.data_recorder);
00955                 mItemStatusVisibility = menu.findItem(R.id.status);
00956                 mItemDebugVisibility = menu.findItem(R.id.debug);
00957                 mItemSave.setEnabled(false);
00958                 mItemExport.setEnabled(false);
00959                 mItemOpen.setEnabled(false);
00960                 mItemPostProcessing.setEnabled(false);
00961                 mItemDataRecorderMode.setEnabled(false);
00962 
00963                 try
00964                 {
00965                         SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(this);
00966                         int renderingType =  sharedPref.getInt(getString(R.string.pref_key_rendering), Integer.parseInt(getString(R.string.pref_default_rendering)));
00967                         if(renderingType == 0)
00968                         {
00969                                 mItemRenderingPointCloud.setChecked(true);
00970                         }
00971                         else if(renderingType == 1)
00972                         {
00973                                 mItemRenderingMesh.setChecked(true);
00974                         }
00975                         else
00976                         {
00977                                 mItemRenderingTextureMesh.setChecked(true);
00978                         }
00979                         RTABMapLib.setMeshRendering(
00980                                         mItemRenderingMesh.isChecked() || mItemRenderingTextureMesh.isChecked(), 
00981                                         mItemRenderingTextureMesh.isChecked());
00982                         
00983                         if(mButtonBackfaceShown != null)
00984                         {
00985                                 mButtonBackfaceShown.setVisibility(mItemRenderingMesh.isChecked() || mItemRenderingTextureMesh.isChecked()?View.VISIBLE:View.INVISIBLE);
00986                         }
00987                 }
00988                 catch(Exception e)
00989                 {
00990                         Log.e(TAG, "Error parsing rendering preferences: " + e.getMessage());
00991                         mToast.makeText(this, String.format("Error parsing rendering preferences: "+e.getMessage()), mToast.LENGTH_LONG).show();
00992                 }
00993 
00994                 updateState(mState);
00995 
00996                 return true;
00997         }
00998         
00999         private long getFreeMemory()
01000         {
01001                 MemoryInfo mi = new MemoryInfo();
01002                 ActivityManager activityManager = (ActivityManager) getSystemService(ACTIVITY_SERVICE);
01003                 activityManager.getMemoryInfo(mi);
01004                 return mi.availMem / 0x100000L; // MB
01005         }
01006         
01007         private void updateStatusTexts()
01008         {
01009                 if(mItemStatusVisibility != null && mItemDebugVisibility != null)
01010                 {
01011                         if((mItemStatusVisibility.isChecked() || mState == State.STATE_VISUALIZING_WHILE_LOADING) && mItemDebugVisibility.isChecked())
01012                         {
01013                                 mRenderer.updateTexts(mStatusTexts);
01014                         }
01015                         else if((mItemStatusVisibility.isChecked() || mState == State.STATE_VISUALIZING_WHILE_LOADING))
01016                         {
01017                                 mRenderer.updateTexts(Arrays.copyOfRange(mStatusTexts, 0, STATUS_TEXTS_POSE_INDEX-1));
01018                         }
01019                         else if(mItemDebugVisibility.isChecked())
01020                         {
01021                                 mRenderer.updateTexts(Arrays.copyOfRange(mStatusTexts, STATUS_TEXTS_POSE_INDEX-1, mStatusTexts.length));
01022                         }
01023                         else
01024                         {
01025                                 mRenderer.updateTexts(null);
01026                         }
01027                 }
01028         }
01029 
01030         private void updateStatsUI(
01031                         int loopClosureId,
01032                         int inliers,
01033                         int matches,
01034                         int rejected,
01035                         float optimizationMaxError,
01036                         float optimizationMaxErrorRatio,
01037                         boolean fastMovement,
01038                         String[] statusTexts)
01039         {
01040                 mStatusTexts = statusTexts;
01041                 updateStatusTexts();
01042 
01043                 if(mButtonPause!=null)
01044                 {
01045                         if(!mButtonPause.isChecked())
01046                         {       
01047                                 //check if we are low in memory
01048                                 long memoryFree = getFreeMemory();
01049                                 long memoryUsed = mFreeMemoryOnStart>memoryFree?mFreeMemoryOnStart-memoryFree:0;
01050                                 
01051                                 if(memoryFree < 400)
01052                                 {
01053                                         mButtonPause.setChecked(true);
01054                                         pauseMapping();
01055                                         
01056                                         if(mMemoryWarningDialog!=null)
01057                                         {
01058                                                 mMemoryWarningDialog.dismiss();
01059                                                 mMemoryWarningDialog = null;
01060                                         }
01061                                         
01062                                         mMemoryWarningDialog = new AlertDialog.Builder(getActivity())
01063                                         .setTitle("Memory is full!")
01064                                         .setCancelable(false)
01065                                         .setMessage(String.format("Scanning has been paused because free memory is too "
01066                                                         + "low (%d MB). You should be able to save the database but some post-processing and exporting options may fail. "
01067                                                         + "\n\nNote that for large environments, you can save multiple databases and "
01068                                                         + "merge them with RTAB-Map Desktop version.", memoryUsed))
01069                                         .setPositiveButton("Ok", new DialogInterface.OnClickListener() {
01070                                                 public void onClick(DialogInterface dialog, int which) {
01071                                                         mMemoryWarningDialog = null;
01072                                                 }
01073                                         })
01074                                         .setNeutralButton("Save", new DialogInterface.OnClickListener() {
01075                                                 public void onClick(DialogInterface dialog, int which) {
01076                                                         saveOnDevice();
01077                                                         mMemoryWarningDialog = null;
01078                                                 }
01079                                         })
01080                                         .create();
01081                                         mMemoryWarningDialog.show();
01082                                 }
01083                                 else if(mMemoryWarningDialog == null && memoryUsed*3 > memoryFree && (mItemDataRecorderMode == null || !mItemDataRecorderMode.isChecked()))
01084                                 {
01085                                         mMemoryWarningDialog = new AlertDialog.Builder(getActivity())
01086                                         .setTitle("Warning: Memory is almost full!")
01087                                         .setCancelable(false)
01088                                         .setMessage(String.format("Free memory (%d MB) should be at least 3 times the "
01089                                                         + "memory used (%d MB) so that some post-processing and exporting options "
01090                                                         + "have enough memory to work correctly. If you just want to save the database "
01091                                                         + "after scanning, you can continue until the next warning.\n\n"
01092                                                         + "Note that showing only point clouds reduces memory needed for rendering.", memoryFree, memoryUsed))
01093                                         .setPositiveButton("Pause", new DialogInterface.OnClickListener() {
01094                                                 public void onClick(DialogInterface dialog, int which) {
01095                                                         mButtonPause.setChecked(true);
01096                                                         pauseMapping();
01097                                                 }
01098                                         })
01099                                         .setNeutralButton("Continue", new DialogInterface.OnClickListener() {
01100                                                 public void onClick(DialogInterface dialog, int which) {
01101                                                 }
01102                                         })
01103                                         .create();
01104                                         mMemoryWarningDialog.show();
01105                                 }
01106                         }
01107                 }
01108 
01109                 
01110                 if(mButtonPause!=null && !mButtonPause.isChecked())
01111                 {
01112                         long currentTime = System.currentTimeMillis()/1000;
01113                         if(loopClosureId > 0)
01114                         {
01115                                 mToast.setText(String.format("Loop closure detected! (%d/%d inliers)", inliers, matches));
01116                                 mToast.show();
01117                         }
01118                         else if(rejected > 0)
01119                         {
01120                                 if(inliers >= Integer.parseInt(mMinInliers))
01121                                 {
01122                                         if(optimizationMaxError > 0.0f)
01123                                         {
01124                                                 mToast.setText(String.format("Loop closure rejected, too high graph optimization error (%.3fm: ratio=%.3f < factor=%sx).", optimizationMaxError, optimizationMaxErrorRatio, mMaxOptimizationError));
01125                                         }
01126                                         else
01127                                         {
01128                                                 mToast.setText(String.format("Loop closure rejected, graph optimization failed! You may try a different Graph Optimizer (see Mapping options)."));
01129                                         }
01130                                 }
01131                                 else
01132                                 {
01133                                         mToast.setText(String.format("Loop closure rejected, not enough inliers (%d/%d < %s).", inliers, matches, mMinInliers));
01134                                 }
01135                                 mToast.show();
01136                         }
01137                         else if(fastMovement)
01138                         {
01139                                 if(currentTime - mLastFastMovementNotificationStamp > 3)
01140                                 {
01141                                         mToast.setText("Move slower... blurry images are not added to map (\"Settings->Mapping...->Maximum Motion Speed\" is enabled).");
01142                                         mToast.show();
01143                                 }
01144                         }
01145                         
01146                         if(!fastMovement)
01147                         {
01148                                 mLastFastMovementNotificationStamp = currentTime;
01149                         }
01150                 }
01151         }
01152 
01153         // called from jni
01154         public void updateStatsCallback(
01155                         final int nodes, 
01156                         final int words, 
01157                         final int points, 
01158                         final int polygons,
01159                         final float updateTime, 
01160                         final int loopClosureId,
01161                         final int highestHypId,
01162                         final int databaseMemoryUsed,
01163                         final int inliers,
01164                         final int matches,
01165                         final int featuresExtracted,
01166                         final float hypothesis,
01167                         final int nodesDrawn,
01168                         final float fps,
01169                         final int rejected,
01170                         final float rehearsalValue,
01171                         final float optimizationMaxError,
01172                         final float optimizationMaxErrorRatio,
01173                         final float distanceTravelled,
01174                         final int fastMovement,
01175                         final float x,
01176                         final float y,
01177                         final float z,
01178                         final float roll,
01179                         final float pitch,
01180                         final float yaw)
01181         {
01182                 if(!DISABLE_LOG) Log.i(TAG, String.format("updateStatsCallback()"));
01183 
01184                 final String[] statusTexts = new String[STATUS_TEXTS_SIZE];
01185                 if(mButtonPause!=null && !mButtonPause.isChecked())
01186                 {
01187                         String updateValue = mUpdateRate.compareTo("0")==0?"Max":mUpdateRate;
01188                         statusTexts[0] = getString(R.string.status)+(mItemDataRecorderMode!=null&&mItemDataRecorderMode.isChecked()?String.format("Recording (%s Hz)", updateValue):mItemLocalizationMode!=null && mItemLocalizationMode.isChecked()?String.format("Localization (%s Hz)", updateValue):String.format("Mapping (%s Hz)", updateValue));
01189                 }
01190                 else
01191                 {
01192                         statusTexts[0] = mStatusTexts[0];
01193                 }
01194                                 
01195                 long memoryFree = getFreeMemory();
01196                 statusTexts[1] = getString(R.string.memory)+(mFreeMemoryOnStart>memoryFree?mFreeMemoryOnStart-memoryFree:0); 
01197                 statusTexts[2] = getString(R.string.free_memory)+memoryFree;
01198                         
01199                 if(loopClosureId > 0)
01200                 {
01201                         ++mTotalLoopClosures;
01202                 }
01203                 
01204                 mMapNodes = nodes;
01205                 
01206                 if(mGPSSaved)
01207                 {
01208                         if(mLastKnownLocation != null)
01209                         {
01210                                 long millisec = System.currentTimeMillis() - mLastKnownLocation.getTime();
01211                                 if(millisec > 1000)
01212                                 {
01213                                         statusTexts[3] = getString(R.string.gps)+String.format("[too old, %d ms]", millisec); 
01214                                 }
01215                                 else
01216                                 {
01217                                         statusTexts[3] = getString(R.string.gps)+
01218                                                         String.format("%.2f %.2f %.2fm %.0fdeg %.0fm", 
01219                                                                         mLastKnownLocation.getLongitude(), 
01220                                                                         mLastKnownLocation.getLatitude(), 
01221                                                                         mLastKnownLocation.getAltitude(), 
01222                                                                         mCompassDeg, 
01223                                                                         mLastKnownLocation.getAccuracy());
01224                                 }
01225                         }
01226                         else
01227                         {
01228                                 statusTexts[3] = getString(R.string.gps)+"[not yet available]";
01229                         }
01230                 }
01231                 
01232                 String formattedDate = new SimpleDateFormat("HH:mm:ss.SSS").format(new Date());
01233                 statusTexts[4] = getString(R.string.time)+formattedDate;
01234                 
01235                 int index = STATUS_TEXTS_POSE_INDEX;
01236                 statusTexts[index++] = getString(R.string.nodes)+nodes+" (" + nodesDrawn + " shown)";
01237                 statusTexts[index++] = getString(R.string.words)+words;
01238                 statusTexts[index++] = getString(R.string.database_size)+databaseMemoryUsed;
01239                 statusTexts[index++] = getString(R.string.points)+points;
01240                 statusTexts[index++] = getString(R.string.polygons)+polygons;
01241                 statusTexts[index++] = getString(R.string.update_time)+(int)(updateTime) + " / " + (mTimeThr.compareTo("0")==0?"No Limit":mTimeThr);
01242                 statusTexts[index++] = getString(R.string.features)+featuresExtracted +" / " + (mMaxFeatures.compareTo("0")==0?"No Limit":mMaxFeatures.compareTo("-1")==0?"Disabled":mMaxFeatures);
01243                 statusTexts[index++] = getString(R.string.rehearsal)+(int)(rehearsalValue*100.0f);
01244                 statusTexts[index++] = getString(R.string.total_loop)+mTotalLoopClosures;
01245                 statusTexts[index++] = getString(R.string.inliers)+inliers;
01246                 statusTexts[index++] = getString(R.string.hypothesis)+(int)(hypothesis*100.0f) +" / " + (int)(Float.parseFloat(mLoopThr)*100.0f) + " (" + (loopClosureId>0?loopClosureId:highestHypId)+")";
01247                 statusTexts[index++] = getString(R.string.fps)+(int)fps+" Hz";
01248                 statusTexts[index++] = getString(R.string.distance)+(int)distanceTravelled+" m";
01249                 statusTexts[index++] = String.format("Pose (x,y,z): %.2f %.2f %.2f", x,y,z);
01250                         
01251                 runOnUiThread(new Runnable() {
01252                                 public void run() {
01253                                         updateStatsUI(loopClosureId, inliers, matches, rejected, optimizationMaxError, optimizationMaxErrorRatio, fastMovement!=0, statusTexts);
01254                                 } 
01255                 });
01256         }
01257 
01258         private void rtabmapInitEventUI(
01259                         int status, 
01260                         String msg)
01261         {
01262                 if(!DISABLE_LOG) Log.i(TAG, String.format("rtabmapInitEventsUI() status=%d msg=%s", status, msg));
01263 
01264                 int optimizedMeshDetected = 0;
01265         
01266                 if(msg.equals("Loading optimized cloud...done!"))
01267                 {
01268                         optimizedMeshDetected = 1;
01269                 }
01270                 else if(msg.equals("Loading optimized mesh...done!"))
01271                 {
01272                         optimizedMeshDetected = 2;
01273                 }
01274                 else if(msg.equals("Loading optimized texture mesh...done!"))
01275                 {
01276                         optimizedMeshDetected = 3;
01277                 }
01278                 if(optimizedMeshDetected > 0)
01279                 {
01280                         resetNoTouchTimer();
01281                         mSavedRenderingType = mItemRenderingPointCloud.isChecked()?0:mItemRenderingMesh.isChecked()?1:2;
01282                         if(optimizedMeshDetected==1)
01283                         {
01284                                 mItemRenderingPointCloud.setChecked(true);
01285                         }
01286                         else if(optimizedMeshDetected==2)
01287                         {
01288                                 mItemRenderingMesh.setChecked(true);
01289                         }
01290                         else // isOBJ
01291                         {
01292                                 mItemRenderingTextureMesh.setChecked(true);
01293                         }
01294                         
01295                         updateState(State.STATE_VISUALIZING_WHILE_LOADING);
01296                         if(mButtonCameraView.getSelectedItemPosition() == 0)
01297                         {
01298                                 setCamera(2);
01299                         }
01300                         mToast.makeText(getActivity(), String.format("Optimized mesh detected in the database, it is shown while the database is loading..."), mToast.LENGTH_LONG).show();
01301                         mProgressDialog.dismiss();
01302                 }
01303                 
01304                 if(mButtonPause!=null)
01305                 {
01306                         if(mButtonPause.isChecked())
01307                         {
01308                                 mStatusTexts[0] = getString(R.string.status)+(status == 1 && msg.isEmpty()?"Paused":msg);
01309                         }
01310                         else if(mItemLocalizationMode!=null && mItemDataRecorderMode!=null)
01311                         {
01312                                 mStatusTexts[0] = getString(R.string.status)+(status == 1 && msg.isEmpty()?(mItemDataRecorderMode!=null&&mItemDataRecorderMode.isChecked()?"Recording":mItemLocalizationMode!=null&&mItemLocalizationMode.isChecked()?"Localization":"Mapping"):msg);
01313                         }
01314                         
01315                         long freeMemory = getFreeMemory();
01316                         mStatusTexts[1] = getString(R.string.memory)+String.valueOf(mFreeMemoryOnStart>freeMemory?mFreeMemoryOnStart-freeMemory:0);
01317                         mStatusTexts[2] = getString(R.string.free_memory)+String.valueOf(freeMemory);
01318                         updateStatusTexts();
01319                 }
01320         }
01321 
01322         //called from jni
01323         public void rtabmapInitEventCallback(
01324                         final int status, 
01325                         final String msg)
01326         {
01327                 if(!DISABLE_LOG) Log.i(TAG, String.format("rtabmapInitEventCallback()"));
01328 
01329                 runOnUiThread(new Runnable() {
01330                         public void run() {
01331                                 rtabmapInitEventUI(status, msg);
01332                         } 
01333                 });
01334         }
01335         
01336         private void updateProgressionUI(
01337                         int count, 
01338                         int max)
01339         {
01340                 if(!DISABLE_LOG) Log.i(TAG, String.format("updateProgressionUI() count=%d max=%s", count, max));
01341 
01342                 mExportProgressDialog.setMax(max);
01343                 mExportProgressDialog.setProgress(count);
01344         }
01345 
01346         //called from jni
01347         public void updateProgressionCallback(
01348                         final int count, 
01349                         final int max)
01350         {
01351                 if(!DISABLE_LOG) Log.i(TAG, String.format("updateProgressionCallback()"));
01352 
01353                 runOnUiThread(new Runnable() {
01354                         public void run() {
01355                                 updateProgressionUI(count, max);
01356                         } 
01357                 });
01358         }
01359 
01360         private void tangoEventUI(
01361                         int type, 
01362                         String key,
01363                         String value)
01364         {
01376                 String str = null;
01377                 if(key.equals("TangoServiceException"))
01378                         str = String.format("Tango service exception: %s", value);
01379                 else if(key.equals("FisheyeOverExposed"))
01380                         ;//str = String.format("The fisheye image is over exposed with average pixel value %s px.", value);
01381                 else if(key.equals("FisheyeUnderExposed"))
01382                         ;//str = String.format("The fisheye image is under exposed with average pixel value %s px.", value);
01383                 else if(key.equals("ColorOverExposed")) 
01384                         ;//str = String.format("The color image is over exposed with average pixel value %s px.", value);
01385                 else if(key.equals("ColorUnderExposed")) 
01386                         ;//str = String.format("The color image is under exposed with average pixel value %s px.", value);
01387                 else if(key.equals("CameraTango")) 
01388                         str = value;
01389                 else if(key.equals("TooFewFeaturesTracked")) 
01390                 {
01391                         if(!value.equals("0"))
01392                         {
01393                                 str = String.format("Too few features (%s) were tracked in the fisheye image. This may result in poor odometry!", value);
01394                         }
01395                 }
01396                 else if(key.equals("TooClose"))
01397                 {
01398                         str = String.format("Too close! Tip: Scan from at least ~1 meter from surfaces.", value);
01399                 }
01400                 else if(key.equals("TangoPoseEventNotReceived"))
01401                 {
01402                         str = String.format("No valid tango pose event received since %s sec.", value);
01403                 }
01404                 else    
01405                 {
01406                         str = String.format("Unknown Tango event detected!? (type=%d, key=%s, value=%s)", type, key, value);
01407                 }
01408                 if(str!=null)
01409                 {
01410                         mToast.setText(str);
01411                         mToast.show();
01412                 }
01413         }
01414 
01415         //called from jni
01416         public void tangoEventCallback(
01417                         final int type, 
01418                         final String key,
01419                         final String value)
01420         {
01421                 if(mButtonPause != null && !mButtonPause.isChecked())
01422                 {
01423                         runOnUiThread(new Runnable() {
01424                                 public void run() {
01425                                         tangoEventUI(type, key, value);
01426                                 } 
01427                         });
01428                 }
01429         }
01430 
01431         private boolean CheckTangoCoreVersion(int minVersion) {
01432                 int versionNumber = 0;
01433                 String packageName = TANGO_PACKAGE_NAME;
01434                 try {
01435                         PackageInfo pi = getApplicationContext().getPackageManager().getPackageInfo(packageName,
01436                                         PackageManager.GET_META_DATA);
01437                         versionNumber = pi.versionCode;
01438                 } catch (NameNotFoundException e) {
01439                         e.printStackTrace();
01440                 }
01441                 return (minVersion <= versionNumber);
01442         }
01443 
01444         private RTABMapActivity getActivity() {return this;}
01445 
01446         private void standardOptimization() {
01447                 mExportProgressDialog.setTitle("Post-Processing");
01448                 mExportProgressDialog.setMessage(String.format("Please wait while optimizing..."));
01449                 mExportProgressDialog.setProgress(0);
01450                 mExportProgressDialog.show();
01451                 
01452                 updateState(State.STATE_PROCESSING);
01453                 Thread workingThread = new Thread(new Runnable() {
01454                         public void run() {
01455                                 final int loopDetected = RTABMapLib.postProcessing(-1);
01456                                 runOnUiThread(new Runnable() {
01457                                         public void run() {
01458                                                 if(mExportProgressDialog.isShowing())
01459                                                 {
01460                                                         mExportProgressDialog.dismiss();
01461                                                         if(loopDetected >= 0)
01462                                                         {
01463                                                                 mTotalLoopClosures+=loopDetected;
01464                                                                 mProgressDialog.setTitle("Post-Processing");
01465                                                                 mProgressDialog.setMessage(String.format("Optimization done! Increasing visual appeal..."));
01466                                                                 mProgressDialog.show();
01467                                                         }
01468                                                         else if(loopDetected < 0)
01469                                                         {
01470                                                                 mToast.makeText(getActivity(), String.format("Optimization failed!"), mToast.LENGTH_LONG).show();
01471                                                         }
01472                                                 }
01473                                                 else
01474                                                 {
01475                                                         mProgressDialog.dismiss();
01476                                                         mToast.makeText(getActivity(), String.format("Optimization canceled"), mToast.LENGTH_LONG).show();
01477                                                 }
01478                                                 updateState(State.STATE_IDLE);
01479                                         }
01480                                 });
01481                         } 
01482                 });
01483                 workingThread.start();
01484         }
01485         
01486         private Handler notouchHandler = new Handler(){
01487         public void handleMessage(Message msg) {
01488         }
01489     };
01490 
01491     private Runnable notouchCallback = new Runnable() {
01492         @Override
01493         public void run() {
01494                 if(!mProgressDialog.isShowing() && !mMenuOpened)
01495                 {
01496                         setNavVisibility(false);
01497                         mHudVisible = false;
01498                     updateState(mState);
01499                 }
01500                 else
01501                 {
01502                         resetNoTouchTimer();
01503                 }
01504         }
01505     };
01506 
01507     public void resetNoTouchTimer(){
01508         resetNoTouchTimer(false);
01509     }
01510     
01511     public void resetNoTouchTimer(boolean showHud){
01512         if(showHud)
01513         {
01514                 mHudVisible = true;
01515                         setNavVisibility(true);
01516                         if(mItemSave != null)
01517                         {
01518                                 updateState(mState);
01519                         }
01520         }
01521                 
01522         notouchHandler.removeCallbacks(notouchCallback);
01523         notouchHandler.postDelayed(notouchCallback, NOTOUCH_TIMEOUT);
01524     }
01525 
01526     public void stopDisconnectTimer(){
01527         notouchHandler.removeCallbacks(notouchCallback);
01528     }
01529                 
01530         private void updateState(State state)
01531         {       
01532                 if(mState == State.STATE_VISUALIZING && state == State.STATE_IDLE && mMapNodes > 100)
01533                 {
01534                         mToast.makeText(getActivity(), String.format("Re-adding %d online clouds, this may take some time...", mMapNodes), mToast.LENGTH_LONG).show();
01535                 }
01536                 mState = state;
01537                 if(!DISABLE_LOG) Log.i(TAG, String.format("updateState() state=%s hud=%d", state.toString(), mHudVisible?1:0));
01538                 switch(state)
01539                 {
01540                 case STATE_PROCESSING:
01541                         mButtonLighting.setVisibility(View.INVISIBLE);
01542                         mButtonWireframe.setVisibility(View.INVISIBLE);
01543                         mButtonCloseVisualization.setVisibility(View.INVISIBLE);
01544                         mButtonSaveOnDevice.setVisibility(View.INVISIBLE);
01545                         mButtonShareOnSketchfab.setVisibility(View.INVISIBLE);
01546                         mItemSave.setEnabled(false);
01547                         mItemExport.setEnabled(false);
01548                         mItemOpen.setEnabled(false);
01549                         mItemPostProcessing.setEnabled(false);
01550                         mItemSettings.setEnabled(false);
01551                         mItemReset.setEnabled(false);
01552                         mItemModes.setEnabled(false);
01553                         mButtonPause.setVisibility(View.INVISIBLE);
01554                         break;
01555                 case STATE_VISUALIZING:
01556                         mButtonLighting.setVisibility(mHudVisible && !mItemRenderingPointCloud.isChecked()?View.VISIBLE:View.INVISIBLE);
01557                         mButtonWireframe.setVisibility(mHudVisible && !mItemRenderingPointCloud.isChecked()?View.VISIBLE:View.INVISIBLE);
01558                         mButtonCloseVisualization.setVisibility(mHudVisible && mButtonPause.isChecked()?View.VISIBLE:View.INVISIBLE);
01559                         mButtonCloseVisualization.setEnabled(true);
01560                         mButtonSaveOnDevice.setVisibility(mHudVisible && mButtonPause.isChecked()?View.VISIBLE:View.INVISIBLE);
01561                         mButtonShareOnSketchfab.setVisibility(mHudVisible && mButtonPause.isChecked()?View.VISIBLE:View.INVISIBLE);
01562                         mItemSave.setEnabled(mButtonPause.isChecked());
01563                         mItemExport.setEnabled(mButtonPause.isChecked() && !mItemDataRecorderMode.isChecked());
01564                         mItemOpen.setEnabled(false);
01565                         mItemPostProcessing.setEnabled(false);
01566                         mItemSettings.setEnabled(true);
01567                         mItemReset.setEnabled(true);
01568                         mItemModes.setEnabled(true);
01569                         mButtonPause.setVisibility(mHudVisible && mItemLocalizationMode.isChecked()?View.VISIBLE:View.GONE);
01570                         mItemLocalizationMode.setEnabled(mButtonPause.isChecked());
01571                         mItemDataRecorderMode.setEnabled(mButtonPause.isChecked());
01572                         break;
01573                 case STATE_VISUALIZING_WHILE_LOADING:
01574                         mButtonLighting.setVisibility(mHudVisible && !mItemRenderingPointCloud.isChecked()?View.VISIBLE:View.INVISIBLE);
01575                         mButtonWireframe.setVisibility(mHudVisible && !mItemRenderingPointCloud.isChecked()?View.VISIBLE:View.INVISIBLE);
01576                         mButtonCloseVisualization.setVisibility(mHudVisible?View.VISIBLE:View.INVISIBLE);
01577                         mButtonCloseVisualization.setEnabled(false);
01578                         mButtonSaveOnDevice.setVisibility(View.INVISIBLE);
01579                         mButtonShareOnSketchfab.setVisibility(View.INVISIBLE);
01580                         mItemSave.setEnabled(false);
01581                         mItemExport.setEnabled(false);
01582                         mItemOpen.setEnabled(false);
01583                         mItemPostProcessing.setEnabled(false);
01584                         mItemSettings.setEnabled(false);
01585                         mItemReset.setEnabled(false);
01586                         mItemModes.setEnabled(false);
01587                         mButtonPause.setVisibility(View.INVISIBLE);
01588                         break;
01589                 default:
01590                         mButtonLighting.setVisibility(View.INVISIBLE);
01591                         mButtonWireframe.setVisibility(View.INVISIBLE);
01592                         mButtonCloseVisualization.setVisibility(View.INVISIBLE);
01593                         mButtonSaveOnDevice.setVisibility(View.INVISIBLE);
01594                         mButtonShareOnSketchfab.setVisibility(View.INVISIBLE);
01595                         mItemSave.setEnabled(mButtonPause.isChecked());
01596                         mItemExport.setEnabled(mButtonPause.isChecked() && !mItemDataRecorderMode.isChecked());
01597                         mItemOpen.setEnabled(mButtonPause.isChecked() && !mItemDataRecorderMode.isChecked());
01598                         mItemPostProcessing.setEnabled(mButtonPause.isChecked() && !mItemDataRecorderMode.isChecked());
01599                         mItemSettings.setEnabled(true);
01600                         mItemReset.setEnabled(true);
01601                         mItemModes.setEnabled(true);
01602                         mButtonPause.setVisibility(mHudVisible?View.VISIBLE:View.INVISIBLE);
01603                         mItemDataRecorderMode.setEnabled(mButtonPause.isChecked());
01604                         break;
01605                 }
01606                 mButtonCameraView.setVisibility(mHudVisible?View.VISIBLE:View.INVISIBLE);
01607                 mButtonBackfaceShown.setVisibility(mHudVisible && (mItemRenderingMesh.isChecked() || mItemRenderingTextureMesh.isChecked())?View.VISIBLE:View.INVISIBLE);
01608                 mSeekBarOrthoCut.setVisibility(mHudVisible && mButtonCameraView.getSelectedItemPosition() == 3?View.VISIBLE:View.INVISIBLE);
01609                 mSeekBarGrid.setVisibility(mHudVisible && mSeekBarGrid.isEnabled() && mButtonCameraView.getSelectedItemPosition() == 3?View.VISIBLE:View.INVISIBLE);
01610         }
01611 
01612         private void pauseMapping() {
01613 
01614                 if(mState != State.STATE_VISUALIZING)
01615                 {
01616                         updateState(State.STATE_IDLE);
01617                 }
01618                 else
01619                 {
01620                         updateState(State.STATE_VISUALIZING);
01621                 }
01622 
01623                 if(mButtonPause.isChecked())
01624                 {
01625                         RTABMapLib.setPausedMapping(true);
01626                         
01627                         mStatusTexts[0] = getString(R.string.status)+"Paused";
01628                         long freeMemory = getFreeMemory();
01629                         mStatusTexts[1] = getString(R.string.memory)+String.valueOf(mFreeMemoryOnStart>freeMemory?mFreeMemoryOnStart-freeMemory:0);
01630                         mStatusTexts[2] = getString(R.string.free_memory)+String.valueOf(freeMemory);
01631                         updateStatusTexts();
01632                         
01633                         mMapIsEmpty = false;
01634                         mDateOnPause = new Date();
01635                         
01636                         long memoryFree = getFreeMemory();
01637                         if(!mOnPause && !mItemLocalizationMode.isChecked() && !mItemDataRecorderMode.isChecked() && memoryFree >= 100 && mMapNodes>2)
01638                         {
01639                                 // Do standard post processing?
01640                                 new AlertDialog.Builder(getActivity())
01641                                 .setTitle("Mapping Paused! Optimize Now?")
01642                                 .setMessage("Do you want to do standard map optimization now? This can be also done later using \"Optimize\" menu.")
01643                                 .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
01644                                         public void onClick(DialogInterface dialog, int which) {
01645                                                 standardOptimization();
01646                                         }
01647                                 })
01648                                 .setNegativeButton("No", new DialogInterface.OnClickListener() {
01649                                         public void onClick(DialogInterface dialog, int which) {
01650                                                 // do nothing...
01651                                         }
01652                                 })
01653                                 .show();
01654                         } 
01655                 }
01656                 else
01657                 {
01658                         if(mMemoryWarningDialog != null)
01659                         {
01660                                 mMemoryWarningDialog.dismiss();
01661                                 mMemoryWarningDialog=null;
01662                         }
01663                         RTABMapLib.setPausedMapping(false);
01664                         mLastFastMovementNotificationStamp = System.currentTimeMillis()/1000;
01665                         
01666                         if(mItemDataRecorderMode.isChecked())
01667                         {
01668                                 mToast.makeText(getActivity(), String.format("Data Recorder Mode: no map is created, only raw data is recorded."), mToast.LENGTH_LONG).show();
01669                         }
01670                         else if(!mMapIsEmpty)
01671                         {
01672                                 if(mItemLocalizationMode!=null && mItemLocalizationMode.isChecked())
01673                                 {
01674                                         mToast.makeText(getActivity(), String.format("Localization mode"), mToast.LENGTH_LONG).show();
01675                                 }
01676                                 else
01677                                 {
01678                                         mToast.makeText(getActivity(), String.format("On resume, a new map is created. Tip: Try relocalizing in the previous area."), mToast.LENGTH_LONG).show();
01679                                 }
01680                         }
01681                         else if(mMapIsEmpty && mItemLocalizationMode!=null && mItemLocalizationMode.isChecked())
01682                         {
01683                                 mItemLocalizationMode.setChecked(false);
01684                                 RTABMapLib.setLocalizationMode(false);
01685                                 mToast.makeText(getActivity(), String.format("Disabled localization mode as the map is empty, now mapping..."), mToast.LENGTH_LONG).show();
01686                         }
01687                 }
01688         }
01689 
01690         public boolean onOptionsItemSelected(MenuItem item) {
01691                 resetNoTouchTimer();
01692                 if(!DISABLE_LOG) Log.i(TAG, "called onOptionsItemSelected; selected item: " + item);
01693                 int itemId = item.getItemId();
01694                 if (itemId == R.id.post_processing_standard)
01695                 {
01696                         standardOptimization();
01697                 }
01698                 else if (itemId == R.id.detect_more_loop_closures)
01699                 {
01700                         mProgressDialog.setTitle("Post-Processing");
01701                         mProgressDialog.setMessage(String.format("Please wait while detecting more loop closures..."));
01702                         mProgressDialog.show();
01703                         updateState(State.STATE_PROCESSING);
01704                         Thread workingThread = new Thread(new Runnable() {
01705                                 public void run() {
01706                                         final int loopDetected = RTABMapLib.postProcessing(2);
01707                                         runOnUiThread(new Runnable() {
01708                                                 public void run() {
01709                                                         mProgressDialog.dismiss();
01710                                                         if(loopDetected >= 0)
01711                                                         {
01712                                                                 mTotalLoopClosures+=loopDetected;
01713                                                                 mToast.makeText(getActivity(), String.format("Detection done! %d new loop closure(s) added.", loopDetected), mToast.LENGTH_SHORT).show();
01714                                                         }
01715                                                         else if(loopDetected < 0)
01716                                                         {
01717                                                                 mToast.makeText(getActivity(), String.format("Detection failed!"), mToast.LENGTH_SHORT).show();
01718                                                         }
01719                                                         updateState(State.STATE_IDLE);
01720                                                 }
01721                                         });
01722                                 } 
01723                         });
01724                         workingThread.start();
01725                 }
01726                 else if (itemId == R.id.global_graph_optimization)
01727                 {
01728                         mProgressDialog.setTitle("Post-Processing");
01729                         mProgressDialog.setMessage(String.format("Global graph optimization..."));
01730                         mProgressDialog.show();
01731                         updateState(State.STATE_PROCESSING);
01732                         Thread workingThread = new Thread(new Runnable() {
01733                                 public void run() {
01734                                         final int value = RTABMapLib.postProcessing(0);
01735                                         runOnUiThread(new Runnable() {
01736                                                 public void run() {
01737                                                         mProgressDialog.dismiss();
01738                                                         if(value >= 0)
01739                                                         {
01740                                                                 mToast.makeText(getActivity(), String.format("Optimization done!"), mToast.LENGTH_SHORT).show();
01741                                                         }
01742                                                         else if(value < 0)
01743                                                         {
01744                                                                 mToast.makeText(getActivity(), String.format("Optimization failed!"), mToast.LENGTH_SHORT).show();
01745                                                         }
01746                                                         updateState(State.STATE_IDLE);
01747                                                 }
01748                                         });
01749                                 } 
01750                         });
01751                         workingThread.start();
01752                 }
01753                 else if (itemId == R.id.polygons_filtering)
01754                 {               
01755                         mProgressDialog.setTitle("Post-Processing");
01756                         mProgressDialog.setMessage(String.format("Noise filtering..."));
01757                         mProgressDialog.show();
01758                         RTABMapLib.postProcessing(4);
01759                 }
01760                 else if (itemId == R.id.gain_compensation_fast)
01761                 {               
01762                         mProgressDialog.setTitle("Post-Processing");
01763                         mProgressDialog.setMessage(String.format("Adjusting Colors (Fast)..."));
01764                         mProgressDialog.show();
01765                         RTABMapLib.postProcessing(5);
01766                 }
01767                 else if (itemId == R.id.gain_compensation_full)
01768                 {               
01769                         mProgressDialog.setTitle("Post-Processing");
01770                         mProgressDialog.setMessage(String.format("Adjusting Colors (Full)..."));
01771                         mProgressDialog.show();
01772                         RTABMapLib.postProcessing(6);
01773                 }
01774                 else if (itemId == R.id.bilateral_filtering)
01775                 {               
01776                         mProgressDialog.setTitle("Post-Processing");
01777                         mProgressDialog.setMessage(String.format("Mesh smoothing..."));
01778                         mProgressDialog.show();
01779                         RTABMapLib.postProcessing(7);
01780                 }
01781                 else if (itemId == R.id.sba)
01782                 {
01783                         mProgressDialog.setTitle("Post-Processing");
01784                         mProgressDialog.setMessage(String.format("Bundle adjustement..."));
01785                         mProgressDialog.show();
01786 
01787                         Thread workingThread = new Thread(new Runnable() {
01788                                 public void run() {
01789                                         final int value = RTABMapLib.postProcessing(1);
01790                                         runOnUiThread(new Runnable() {
01791                                                 public void run() {
01792                                                         mProgressDialog.dismiss();
01793                                                         if(value >= 0)
01794                                                         {
01795                                                                 mToast.makeText(getActivity(), String.format("Optimization done!"), mToast.LENGTH_SHORT).show();
01796                                                         }
01797                                                         else if(value < 0)
01798                                                         {
01799                                                                 mToast.makeText(getActivity(), String.format("Optimization failed!"), mToast.LENGTH_SHORT).show();
01800                                                         }
01801                                                 }
01802                                         });
01803                                 } 
01804                         });
01805                         workingThread.start();
01806                 }
01807                 else if(itemId == R.id.status)
01808                 {
01809                         item.setChecked(!item.isChecked());
01810                         updateStatusTexts();
01811                 }
01812                 else if(itemId == R.id.debug)
01813                 {
01814                         item.setChecked(!item.isChecked());
01815                         updateStatusTexts();
01816                 }
01817                 else if(itemId == R.id.mesh || itemId == R.id.texture_mesh || itemId == R.id.point_cloud)
01818                 {
01819                         item.setChecked(true);
01820                         RTABMapLib.setMeshRendering(
01821                                         mItemRenderingMesh.isChecked() || mItemRenderingTextureMesh.isChecked(), 
01822                                         mItemRenderingTextureMesh.isChecked());
01823                         
01824                         resetNoTouchTimer();
01825                         
01826                         if(mState != State.STATE_VISUALIZING)
01827                         {
01828                                 // save preference
01829                                 int type = mItemRenderingPointCloud.isChecked()?0:mItemRenderingMesh.isChecked()?1:2;
01830                                 SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(this);
01831                                 SharedPreferences.Editor editor = sharedPref.edit();
01832                                 editor.putInt(getString(R.string.pref_key_rendering), type);
01833                                 // Commit the edits!
01834                                 editor.commit();
01835                         }
01836                 }
01837                 else if(itemId == R.id.map_shown)
01838                 {
01839                         item.setChecked(!item.isChecked());
01840                         RTABMapLib.setMapCloudShown(item.isChecked());
01841                 }
01842                 else if(itemId == R.id.odom_shown)
01843                 {
01844                         item.setChecked(!item.isChecked());
01845                         RTABMapLib.setOdomCloudShown(item.isChecked());
01846                 }
01847                 else if(itemId == R.id.localization_mode)
01848                 {
01849                         item.setChecked(!item.isChecked());
01850                         RTABMapLib.setLocalizationMode(item.isChecked());
01851                         if(mState == State.STATE_VISUALIZING)
01852                         {
01853                                 mButtonPause.setVisibility(mItemLocalizationMode.isChecked()?View.VISIBLE:View.GONE);
01854                         }
01855                 }
01856                 else if(itemId == R.id.trajectory_mode)
01857                 {
01858                         item.setChecked(!item.isChecked());
01859                         RTABMapLib.setTrajectoryMode(item.isChecked());
01860                         setCamera(item.isChecked()?2:1);
01861                 }
01862                 else if(itemId == R.id.graph_optimization)
01863                 {
01864                         item.setChecked(!item.isChecked());
01865                         RTABMapLib.setGraphOptimization(item.isChecked());
01866                 }
01867                 else if(itemId == R.id.graph_visible)
01868                 {
01869                         item.setChecked(!item.isChecked());
01870                         RTABMapLib.setGraphVisible(item.isChecked());
01871                 }
01872                 else if(itemId == R.id.grid_visible)
01873                 {
01874                         item.setChecked(!item.isChecked());
01875                         mSeekBarGrid.setEnabled(item.isChecked());
01876                         mSeekBarGrid.setVisibility(mHudVisible && mSeekBarGrid.isEnabled()&&mButtonCameraView.getSelectedItemPosition() == 3?View.VISIBLE:View.INVISIBLE);
01877                         RTABMapLib.setGridVisible(item.isChecked());
01878                 }
01879                 else if (itemId == R.id.save)
01880                 {
01881                         AlertDialog.Builder builder = new AlertDialog.Builder(this);
01882                         builder.setTitle("RTAB-Map Database Name (*.db):");
01883                         final EditText input = new EditText(this);
01884                         input.setInputType(InputType.TYPE_CLASS_TEXT); 
01885                         if(mOpenedDatabasePath.isEmpty())
01886                         {
01887                                 String timeStamp = new SimpleDateFormat("yyMMdd-HHmmss").format(mDateOnPause);
01888                                 input.setText(timeStamp);
01889                         }
01890                         else
01891                         {
01892                                 File f = new File(mOpenedDatabasePath);
01893                                 String name = f.getName();
01894                                 input.setText(name.substring(0,name.lastIndexOf(".")));
01895                         }
01896                         input.setImeOptions(EditorInfo.IME_FLAG_NO_EXTRACT_UI);
01897                         input.setSelectAllOnFocus(true);
01898                         input.selectAll();
01899                         builder.setView(input);
01900                         builder.setPositiveButton("OK", new DialogInterface.OnClickListener() {
01901                                 @Override
01902                                 public void onClick(DialogInterface dialog, int which)
01903                                 {
01904                                         final String fileName = input.getText().toString();  
01905                                         dialog.dismiss();
01906                                         if(!fileName.isEmpty())
01907                                         {
01908                                                 File newFile = new File(mWorkingDirectory + fileName + ".db");
01909                                                 if(newFile.exists())
01910                                                 {
01911                                                         new AlertDialog.Builder(getActivity())
01912                                                         .setTitle("File Already Exists")
01913                                                         .setMessage("Do you want to overwrite the existing file?")
01914                                                         .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
01915                                                                 public void onClick(DialogInterface dialog, int which) {
01916                                                                         saveDatabase(fileName);
01917                                                                 }
01918                                                         })
01919                                                         .setNegativeButton("No", new DialogInterface.OnClickListener() {
01920                                                                 public void onClick(DialogInterface dialog, int which) {
01921                                                                         dialog.dismiss();
01922                                                                         resetNoTouchTimer(true);
01923                                                                 }
01924                                                         })
01925                                                         .show();
01926                                                 }
01927                                                 else
01928                                                 {
01929                                                         saveDatabase(fileName);
01930                                                 }
01931                                         }
01932                                 }
01933                         });
01934                         AlertDialog alertToShow = builder.create();
01935                         alertToShow.getWindow().setSoftInputMode(WindowManager.LayoutParams.SOFT_INPUT_STATE_VISIBLE);
01936                         alertToShow.show();
01937                 }
01938                 else if(itemId == R.id.reset)
01939                 {
01940                         mTotalLoopClosures = 0;
01941                         
01942                         int index = STATUS_TEXTS_POSE_INDEX;
01943                         mMapNodes = 0;
01944                         mStatusTexts[index++] = getString(R.string.nodes)+0;
01945                         mStatusTexts[index++] = getString(R.string.words)+0;
01946                         mStatusTexts[index++] = getString(R.string.database_size)+0;
01947                         mStatusTexts[index++] = getString(R.string.points)+0;
01948                         mStatusTexts[index++] = getString(R.string.polygons)+0;
01949                         mStatusTexts[index++] = getString(R.string.update_time)+0;
01950                         mStatusTexts[index++] = getString(R.string.features)+0;
01951                         mStatusTexts[index++] = getString(R.string.rehearsal)+0;
01952                         mStatusTexts[index++] = getString(R.string.total_loop)+0;
01953                         mStatusTexts[index++] = getString(R.string.inliers)+0;
01954                         mStatusTexts[index++] = getString(R.string.hypothesis)+0;
01955                         mStatusTexts[index++] = getString(R.string.fps)+0;
01956                         mStatusTexts[index++] = getString(R.string.distance)+0;
01957                         mStatusTexts[index++] = String.format("Pose (x,y,z): 0 0 0");
01958                         updateStatusTexts();
01959 
01960                         mOpenedDatabasePath = "";
01961                         SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(this);
01962                         boolean databaseInMemory = sharedPref.getBoolean(getString(R.string.pref_key_db_in_memory), Boolean.parseBoolean(getString(R.string.pref_default_db_in_memory)));
01963                         String tmpDatabase = mWorkingDirectory+RTABMAP_TMP_DB;
01964                         RTABMapLib.openDatabase(tmpDatabase, databaseInMemory, false);
01965                         
01966                         mMapIsEmpty = true;
01967                         mItemSave.setEnabled(false);
01968                         mItemExport.setEnabled(false);
01969                         mItemPostProcessing.setEnabled(false);
01970                         updateState(State.STATE_IDLE);
01971                 }
01972                 else if(itemId == R.id.data_recorder)
01973                 {
01974                         final boolean dataRecorderOldState = item.isChecked();
01975                         new AlertDialog.Builder(getActivity())
01976                         .setTitle("Data Recorder Mode")
01977                         .setMessage("Changing from/to data recorder mode will close the current session. Do you want to continue?")
01978                         .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
01979                                 public void onClick(DialogInterface dialog, int which) {                  
01980                                         // reset
01981                                         mTotalLoopClosures = 0;
01982                                         int index = STATUS_TEXTS_POSE_INDEX;
01983                                         mMapNodes = 0;
01984                                         mStatusTexts[index++] = getString(R.string.nodes)+0;
01985                                         mStatusTexts[index++] = getString(R.string.words)+0;
01986                                         mStatusTexts[index++] = getString(R.string.database_size)+0;
01987                                         mStatusTexts[index++] = getString(R.string.points)+0;
01988                                         mStatusTexts[index++] = getString(R.string.polygons)+0;
01989                                         mStatusTexts[index++] = getString(R.string.update_time)+0;
01990                                         mStatusTexts[index++] = getString(R.string.features)+0;
01991                                         mStatusTexts[index++] = getString(R.string.rehearsal)+0;
01992                                         mStatusTexts[index++] = getString(R.string.total_loop)+0;
01993                                         mStatusTexts[index++] = getString(R.string.inliers)+0;
01994                                         mStatusTexts[index++] = getString(R.string.hypothesis)+0;
01995                                         mStatusTexts[index++] = getString(R.string.fps)+0;
01996                                         mStatusTexts[index++] = getString(R.string.distance)+0;
01997                                         mStatusTexts[index++] = String.format("Pose (x,y,z): 0 0 0");
01998                                         updateStatusTexts();
01999 
02000                                         mItemDataRecorderMode.setChecked(!dataRecorderOldState);
02001                                         RTABMapLib.setDataRecorderMode(mItemDataRecorderMode.isChecked());
02002 
02003                                         mOpenedDatabasePath = "";
02004                                         SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(getActivity());
02005                                         boolean databaseInMemory = sharedPref.getBoolean(getString(R.string.pref_key_db_in_memory), Boolean.parseBoolean(getString(R.string.pref_default_db_in_memory)));
02006                                         String tmpDatabase = mWorkingDirectory+RTABMAP_TMP_DB;
02007                                         RTABMapLib.openDatabase(tmpDatabase, databaseInMemory, false);
02008 
02009                                         mItemOpen.setEnabled(!mItemDataRecorderMode.isChecked() && mButtonPause.isChecked());
02010                                         mItemPostProcessing.setEnabled(!mItemDataRecorderMode.isChecked() && mButtonPause.isChecked());
02011                                         mItemExport.setEnabled(!mItemDataRecorderMode.isChecked() && mButtonPause.isChecked());
02012 
02013                                         mItemLocalizationMode.setEnabled(!mItemDataRecorderMode.isChecked());              
02014 
02015                                         if(mItemDataRecorderMode.isChecked())
02016                                         {
02017                                                 mToast.makeText(getActivity(), String.format("Data recorder mode activated! Tip: You can increase data update rate in Parameters menu under Mapping options."), mToast.LENGTH_LONG).show();
02018                                         }
02019                                         else
02020                                         {
02021                                                 mToast.makeText(getActivity(), String.format("Data recorder mode deactivated!"), mToast.LENGTH_LONG).show();
02022                                         }
02023                                 }
02024                         })
02025                         .setNegativeButton("No", new DialogInterface.OnClickListener() {
02026                                 public void onClick(DialogInterface dialog, int which) {
02027                                         dialog.dismiss();
02028                                 }
02029                         })
02030                         .show();
02031                 }
02032                 else if(itemId == R.id.export_point_cloud ||
02033                                 itemId == R.id.export_point_cloud_highrez)
02034                 {
02035                         final boolean regenerateCloud = itemId == R.id.export_point_cloud_highrez;
02036 
02037                         export(false, false, regenerateCloud, false, 0);
02038                 }
02039                 else if(itemId == R.id.export_optimized_mesh ||
02040                                 itemId == R.id.export_optimized_mesh_texture)
02041                 {
02042                         final boolean isOBJ = itemId == R.id.export_optimized_mesh_texture;
02043                         
02044                 RelativeLayout linearLayout = new RelativeLayout(this);
02045                 final NumberPicker aNumberPicker = new NumberPicker(this);
02046                 aNumberPicker.setMaxValue(9);
02047                 aNumberPicker.setMinValue(0);
02048                 aNumberPicker.setWrapSelectorWheel(false);
02049                 aNumberPicker.setDescendantFocusability(NumberPicker.FOCUS_BLOCK_DESCENDANTS);
02050                 aNumberPicker.setFormatter(new NumberPicker.Formatter() {
02051                     @Override
02052                     public String format(int i) {
02053                         if(i==0)
02054                         {
02055                                 return "No Limit";
02056                         }
02057                         return String.format("%d00 000", i);
02058                     }
02059                 });
02060                 aNumberPicker.setValue(2);
02061 
02062                 // Fix to correctly show value on first render
02063                 try {
02064                         Method method = aNumberPicker.getClass().getDeclaredMethod("changeValueByOne", boolean.class);
02065                         method.setAccessible(true);
02066                         method.invoke(aNumberPicker, true);
02067                 } catch (NoSuchMethodException e) {
02068                         e.printStackTrace();
02069                 } catch (IllegalArgumentException e) {
02070                         e.printStackTrace();
02071                 } catch (IllegalAccessException e) {
02072                         e.printStackTrace();
02073                 } catch (InvocationTargetException e) {
02074                         e.printStackTrace();
02075                 }
02076 
02077 
02078                 RelativeLayout.LayoutParams params = new RelativeLayout.LayoutParams(50, 50);
02079                 RelativeLayout.LayoutParams numPicerParams = new RelativeLayout.LayoutParams(RelativeLayout.LayoutParams.WRAP_CONTENT, RelativeLayout.LayoutParams.WRAP_CONTENT);
02080                 numPicerParams.addRule(RelativeLayout.CENTER_HORIZONTAL);
02081 
02082                 linearLayout.setLayoutParams(params);
02083                 linearLayout.addView(aNumberPicker,numPicerParams);
02084 
02085                 AlertDialog.Builder alertDialogBuilder = new AlertDialog.Builder(this);
02086                 alertDialogBuilder.setTitle("Maximum polygons");
02087                 alertDialogBuilder.setView(linearLayout);
02088                 alertDialogBuilder
02089                         .setCancelable(false)
02090                         .setPositiveButton("Ok",
02091                                 new DialogInterface.OnClickListener() {
02092                                     public void onClick(DialogInterface dialog,
02093                                                         int id) {
02094                                         export(isOBJ, true, false, true, aNumberPicker.getValue()*100000);
02095                                     }
02096                                 })
02097                         .setNegativeButton("Cancel",
02098                                 new DialogInterface.OnClickListener() {
02099                                     public void onClick(DialogInterface dialog,
02100                                                         int id) {
02101                                         dialog.cancel();
02102                                     }
02103                                 });
02104                 AlertDialog alertDialog = alertDialogBuilder.create();
02105                 alertDialog.show();
02106                 }
02107                 else if(itemId == R.id.open)
02108                 {
02109                         openDatabase();
02110                 }
02111                 else if(itemId == R.id.settings)
02112                 {
02113                         Intent intent = new Intent(getActivity(), SettingsActivity.class);
02114                         startActivity(intent);
02115                         mBlockBack = true;
02116                 }
02117                 else if(itemId == R.id.about)
02118                 {
02119                         AboutDialog about = new AboutDialog(this);
02120                         about.setTitle("About RTAB-Map");
02121                         about.show();
02122                 }
02123 
02124                 return true;
02125         }
02126         
02127         private void openDatabase()
02128         {
02129                 final String[] files = Util.loadFileList(mWorkingDirectory, true);
02130                 if(files.length > 0)
02131                 {
02132                         String[] filesWithSize = new String[files.length];
02133                         for(int i = 0; i<filesWithSize.length; ++i)
02134                         {
02135                                 File filePath = new File(mWorkingDirectory+files[i]);
02136                                 long mb = filePath.length()/(1024*1024);
02137                                 filesWithSize[i] = files[i] + " ("+mb+" MB)";
02138                         }
02139                         
02140                         ArrayList<HashMap<String, String> > arrayList = new ArrayList<HashMap<String, String> >();
02141                 for (int i = 0; i < filesWithSize.length; i++) {
02142                     HashMap<String, String> hashMap = new HashMap<String, String>();//create a hashmap to store the data in key value pair
02143                     hashMap.put("name", filesWithSize[i]);
02144                     hashMap.put("path", mWorkingDirectory + files[i]);
02145                     arrayList.add(hashMap);//add the hashmap into arrayList
02146                 }
02147                 String[] from = {"name", "path"};//string array
02148                 int[] to = {R.id.textView, R.id.imageView};//int array of views id's
02149                 DatabaseListArrayAdapter simpleAdapter = new DatabaseListArrayAdapter(this, arrayList, R.layout.database_list, from, to);//Create object and set the parameters for simpleAdapter
02150 
02151                         AlertDialog.Builder builder = new AlertDialog.Builder(this);
02152                         builder.setTitle("Choose Your File (*.db)");
02153                         builder.setAdapter(simpleAdapter, new DialogInterface.OnClickListener() {
02154                         //builder.setItems(filesWithSize, new DialogInterface.OnClickListener() {
02155                                 public void onClick(DialogInterface dialog, final int which) {
02156                                                                                         
02157                                         // Adjust color now?
02158                                         new AlertDialog.Builder(getActivity())
02159                                         .setTitle("Opening database...")
02160                                         .setMessage("Do you want to adjust colors now?\nThis can be done later under Optimize menu.")
02161                                         .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
02162                                                 public void onClick(DialogInterface dialog, int whichIn) {
02163                                                         openDatabase(files[which], true);
02164                                                 }
02165                                         })
02166                                         .setNeutralButton("No", new DialogInterface.OnClickListener() {
02167                                                 public void onClick(DialogInterface dialog, int whichIn) {
02168                                                         openDatabase(files[which], false);
02169                                                 }
02170                                         })
02171                                         .show();
02172                                         return;
02173                                 }
02174                         });
02175 
02176                         final AlertDialog ad = builder.create(); //don't show dialog yet
02177                         ad.setOnShowListener(new OnShowListener() 
02178                         {                       
02179                                 @Override
02180                                 public void onShow(DialogInterface dialog) 
02181                                 {       
02182                                         ListView lv = ad.getListView(); 
02183                                         ad.registerForContextMenu(lv);
02184                                         lv.setOnCreateContextMenuListener(new OnCreateContextMenuListener() {
02185 
02186                                                 @Override
02187                                                 public void onCreateContextMenu(ContextMenu menu, View v, ContextMenuInfo menuInfo) {
02188 
02189                                                         if (v.getId()==ad.getListView().getId()) {
02190                                                                 AdapterView.AdapterContextMenuInfo info = (AdapterView.AdapterContextMenuInfo)menuInfo;
02191                                                                 final int position = info.position;
02192                                                                 menu.setHeaderTitle(files[position]);
02193                                                                 menu.add(Menu.NONE, 0, 0, "Rename").setOnMenuItemClickListener(new OnMenuItemClickListener() {
02194                                                                         @Override
02195                                                                         public boolean onMenuItemClick(MenuItem item) {
02196                                                                                 AlertDialog.Builder builderRename = new AlertDialog.Builder(getActivity());
02197                                                                                 builderRename.setTitle("RTAB-Map Database Name (*.db):");
02198                                                                                 final EditText input = new EditText(getActivity());
02199                                                                                 input.setInputType(InputType.TYPE_CLASS_TEXT); 
02200                                                                                 input.setText("");
02201                                                                                 input.setImeOptions(EditorInfo.IME_FLAG_NO_EXTRACT_UI);
02202                                                                                 input.setSelectAllOnFocus(true);
02203                                                                                 input.selectAll();
02204                                                                                 builderRename.setView(input);
02205                                                                                 builderRename.setPositiveButton("OK", new DialogInterface.OnClickListener() {
02206                                                                                         @Override
02207                                                                                         public void onClick(DialogInterface dialog, int which)
02208                                                                                         {
02209                                                                                                 final String fileName = input.getText().toString();  
02210                                                                                                 dialog.dismiss();
02211                                                                                                 if(!fileName.isEmpty())
02212                                                                                                 {
02213                                                                                                         File newFile = new File(mWorkingDirectory + fileName + ".db");
02214                                                                                                         if(newFile.exists())
02215                                                                                                         {
02216                                                                                                                 new AlertDialog.Builder(getActivity())
02217                                                                                                                 .setTitle("File Already Exists")
02218                                                                                                                 .setMessage(String.format("Name %s already used, choose another name.", fileName))
02219                                                                                                                 .show();
02220                                                                                                         }
02221                                                                                                         else
02222                                                                                                         {
02223                                                                                                                 File from = new File(mWorkingDirectory, files[position]);
02224                                                                                                         File to   = new File(mWorkingDirectory, fileName + ".db");
02225                                                                                                         from.renameTo(to);
02226                                                                                                         ad.dismiss();
02227                                                                                                         resetNoTouchTimer(true);
02228                                                                                                         }
02229                                                                                                 }
02230                                                                                         }
02231                                                                                 });
02232                                                                                 AlertDialog alertToShow = builderRename.create();
02233                                                                                 alertToShow.getWindow().setSoftInputMode(WindowManager.LayoutParams.SOFT_INPUT_STATE_VISIBLE);
02234                                                                                 alertToShow.show();
02235                                                                                 return true;
02236                                                                         }
02237                                                                 });
02238                                                                 menu.add(Menu.NONE, 1, 1, "Delete").setOnMenuItemClickListener(new OnMenuItemClickListener() {
02239                                                                         @Override
02240                                                                         public boolean onMenuItemClick(MenuItem item) {
02241                                                                                 DialogInterface.OnClickListener dialogClickListener = new DialogInterface.OnClickListener() {
02242                                                                                     @Override
02243                                                                                     public void onClick(DialogInterface dialog, int which) {
02244                                                                                         switch (which){
02245                                                                                         case DialogInterface.BUTTON_POSITIVE:
02246                                                                                                 Log.e(TAG, String.format("Yes delete %s!", files[position]));
02247                                                                                                 (new File(mWorkingDirectory+files[position])).delete();
02248                                                                                                 ad.dismiss();
02249                                                                                                 resetNoTouchTimer(true);
02250                                                                                             break;
02251 
02252                                                                                         case DialogInterface.BUTTON_NEGATIVE:
02253                                                                                             //No button clicked
02254                                                                                             break;
02255                                                                                         }
02256                                                                                     }
02257                                                                                 };
02258                                                                                 AlertDialog.Builder builder = new AlertDialog.Builder(getActivity());
02259                                                                                 builder.setTitle(String.format("Delete %s", files[position]))
02260                                                                                     .setMessage("Are you sure?")
02261                                                                                     .setPositiveButton("Yes", dialogClickListener)
02262                                                                                     .setNegativeButton("No", dialogClickListener).show();
02263                                                                                 return true;
02264                                                                         }
02265                                                                 });
02266                                                                 menu.add(Menu.NONE, 2, 2, "Share").setOnMenuItemClickListener(new OnMenuItemClickListener() {
02267                                                                         @Override
02268                                                                         public boolean onMenuItemClick(MenuItem item) {
02269                                                                                 // Send to...
02270                                                                                 File f = new File(mWorkingDirectory+files[position]);
02271                                                                                 final int fileSizeMB = (int)f.length()/(1024 * 1024);
02272                                                                                 Intent shareIntent = new Intent();
02273                                                                                 shareIntent.setAction(Intent.ACTION_SEND);
02274                                                                                 shareIntent.putExtra(Intent.EXTRA_STREAM, Uri.fromFile(f));
02275                                                                                 shareIntent.setType("application/octet-stream");
02276                                                                                 startActivity(Intent.createChooser(shareIntent, String.format("Sharing database \"%s\" (%d MB)...", files[position], fileSizeMB)));
02277                                                                                 ad.dismiss();
02278                                                                         resetNoTouchTimer(true);
02279                                                                                 return true;
02280                                                                         }
02281                                                                 });
02282                                                         }
02283                                                 }                                                       
02284                                         });
02285                                 }
02286                         });
02287                         ad.show();
02288                 }       
02289         }
02290         
02291         private void export(final boolean isOBJ, final boolean meshing, final boolean regenerateCloud, final boolean optimized, final int optimizedMaxPolygons)
02292         {
02293                 final String extension = isOBJ? ".obj" : ".ply";
02294                 
02295                 // get Export settings
02296                 SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(this);
02297                 final String cloudVoxelSizeStr = sharedPref.getString(getString(R.string.pref_key_cloud_voxel), getString(R.string.pref_default_cloud_voxel));
02298                 final float cloudVoxelSize = Float.parseFloat(cloudVoxelSizeStr);
02299                 final int textureSize = isOBJ?Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_texture_size), getString(R.string.pref_default_texture_size))):0;
02300                 final int textureCount = Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_texture_count), getString(R.string.pref_default_texture_count)));
02301                 final int normalK = Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_normal_k), getString(R.string.pref_default_normal_k)));
02302                 final float maxTextureDistance = Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_max_texture_distance), getString(R.string.pref_default_max_texture_distance)));
02303                 final int minTextureClusterSize = Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_min_texture_cluster_size), getString(R.string.pref_default_min_texture_cluster_size)));
02304                 final float optimizedVoxelSize = cloudVoxelSize;
02305                 final int optimizedDepth = Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_opt_depth), getString(R.string.pref_default_opt_depth)));
02306                 final float optimizedColorRadius = Float.parseFloat(sharedPref.getString(getString(R.string.pref_key_opt_color_radius), getString(R.string.pref_default_opt_color_radius)));
02307                 final boolean optimizedCleanWhitePolygons = sharedPref.getBoolean(getString(R.string.pref_key_opt_clean_white), Boolean.parseBoolean(getString(R.string.pref_default_opt_clean_white)));
02308                 final int optimizedMinClusterSize = Integer.parseInt(sharedPref.getString(getString(R.string.pref_key_opt_min_cluster_size), getString(R.string.pref_default_opt_min_cluster_size)));
02309                 final boolean blockRendering = sharedPref.getBoolean(getString(R.string.pref_key_block_render), Boolean.parseBoolean(getString(R.string.pref_default_block_render)));
02310 
02311                 
02312                 mExportProgressDialog.setTitle("Exporting");
02313                 mExportProgressDialog.setMessage(String.format("Please wait while preparing data to export..."));
02314                 mExportProgressDialog.setProgress(0);
02315                 
02316                 final State previousState = mState;
02317                 
02318                 mExportProgressDialog.show();
02319                 updateState(State.STATE_PROCESSING);
02320                                 
02321                 Thread exportThread = new Thread(new Runnable() {
02322                         public void run() {
02323 
02324                                 final long startTime = System.currentTimeMillis()/1000;
02325 
02326                                 final boolean success = RTABMapLib.exportMesh(
02327                                                 cloudVoxelSize,
02328                                                 regenerateCloud,
02329                                                 meshing,
02330                                                 textureSize,
02331                                                 textureCount,
02332                                                 normalK,
02333                                                 optimized,
02334                                                 optimizedVoxelSize,
02335                                                 optimizedDepth,
02336                                                 optimizedMaxPolygons,
02337                                                 optimizedColorRadius,
02338                                                 optimizedCleanWhitePolygons,
02339                                                 optimizedMinClusterSize,
02340                                                 maxTextureDistance,
02341                                                 minTextureClusterSize,
02342                                                 blockRendering);
02343                                 runOnUiThread(new Runnable() {
02344                                         public void run() {
02345                                                 if(mExportProgressDialog.isShowing())
02346                                                 {                                                       
02347                                                         if(success)
02348                                                         {                                                               
02349                                                                 if(!meshing && cloudVoxelSize>0.0f)
02350                                                                 {
02351                                                                         mToast.makeText(getActivity(), String.format("Cloud assembled and voxelized at %s m.", cloudVoxelSizeStr), mToast.LENGTH_LONG).show();
02352                                                                 }
02353                                                                 
02354                                                                 final long endTime = System.currentTimeMillis()/1000;
02355                                                                 
02356                                                                 if(endTime-startTime > 10)
02357                                                                 {
02358                                                                         // build notification
02359                                                                         // the addAction re-use the same intent to keep the example short
02360                                                                         SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(getActivity());
02361                                                                         boolean notifySound = sharedPref.getBoolean(getString(R.string.pref_key_notification_sound), Boolean.parseBoolean(getString(R.string.pref_default_notification_sound)));
02362                                                                         Notification n  = new Notification.Builder(getActivity())
02363                                                                         .setContentTitle(getString(R.string.app_name))
02364                                                                         .setContentText("Data generated and ready to be exported!")
02365                                                                         .setSmallIcon(R.drawable.ic_launcher)
02366                                                                         .setDefaults(notifySound?Notification.DEFAULT_SOUND:0)
02367                                                                         .setAutoCancel(true).build();
02368                                                 
02369                                                                         NotificationManager notificationManager = 
02370                                                                                         (NotificationManager) getSystemService(NOTIFICATION_SERVICE);
02371                                                 
02372                                                                         notificationManager.notify(0, n); 
02373                                                                 }
02374 
02375                                                                 // Visualize the result?
02376                                                                 AlertDialog d = new AlertDialog.Builder(getActivity())
02377                                                                 .setCancelable(false)
02378                                                                 .setTitle("Export Successful! (" + (endTime-startTime) + " sec)")
02379                                                                 .setMessage(Html.fromHtml("Do you want visualize the result before saving to file or sharing to <a href=\"https://sketchfab.com/about\">Sketchfab</a>?"))
02380                                                                 .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
02381                                                                         public void onClick(DialogInterface dialog, int which) {
02382                                                                                 resetNoTouchTimer(true);
02383                                                                                 mSavedRenderingType = mItemRenderingPointCloud.isChecked()?0:mItemRenderingMesh.isChecked()?1:2;
02384                                                                                 if(!meshing)
02385                                                                                 {
02386                                                                                         mItemRenderingPointCloud.setChecked(true);
02387                                                                                 }
02388                                                                                 else if(!isOBJ)
02389                                                                                 {
02390                                                                                         mItemRenderingMesh.setChecked(true);
02391                                                                                 }
02392                                                                                 else // isOBJ
02393                                                                                 {
02394                                                                                         mItemRenderingTextureMesh.setChecked(true);
02395                                                                                 }
02396                                                                                 if(!optimizedCleanWhitePolygons)
02397                                                                                 {
02398                                                                                         mButtonLighting.setChecked(true);
02399                                                                                         RTABMapLib.setLighting(true);
02400                                                                                 }
02401                                                                                 updateState(State.STATE_VISUALIZING);
02402                                                                                 RTABMapLib.postExportation(true);
02403                                                                                 if(mButtonCameraView.getSelectedItemPosition() == 0)
02404                                                                                 {
02405                                                                                         setCamera(2);
02406                                                                                 }
02407                                                                         }
02408                                                                 })
02409                                                                 .setNegativeButton("No", new DialogInterface.OnClickListener() {
02410                                                                         public void onClick(DialogInterface dialog, int which) {
02411                                                                                 updateState(State.STATE_IDLE);
02412                                                                                 RTABMapLib.postExportation(false);
02413                                                                                 
02414                                                                                 AlertDialog d2 = new AlertDialog.Builder(getActivity())
02415                                                                                 .setCancelable(false)
02416                                                                                 .setTitle("Save to...")
02417                                                                                 .setMessage(Html.fromHtml("Do you want to share to <a href=\"https://sketchfab.com/about\">Sketchfab</a> or save it on device?"))
02418                                                                                 .setPositiveButton("Share to Sketchfab", new DialogInterface.OnClickListener() {
02419                                                                                         public void onClick(DialogInterface dialog, int which) {
02420                                                                                                 shareToSketchfab();
02421                                                                                         }
02422                                                                                 })
02423                                                                                 .setNegativeButton("Save on device", new DialogInterface.OnClickListener() {
02424                                                                                         public void onClick(DialogInterface dialog, int which) {
02425                                                                                                 saveOnDevice();
02426                                                                                         }
02427                                                                                 })
02428                                                                                 .setNeutralButton("Cancel", new DialogInterface.OnClickListener() {
02429                                                                                         public void onClick(DialogInterface dialog, int which) {
02430                                                                                                 resetNoTouchTimer(true);
02431                                                                                         }
02432                                                                                 })
02433                                                                                 .create();
02434                                                                                 d2.show();
02435                                                                                 // Make the textview clickable. Must be called after show()
02436                                                                             ((TextView)d2.findViewById(android.R.id.message)).setMovementMethod(LinkMovementMethod.getInstance());
02437                                                                         }
02438                                                                 })
02439                                                                 .create();
02440                                                                 d.show();
02441                                                                 // Make the textview clickable. Must be called after show()
02442                                                             ((TextView)d.findViewById(android.R.id.message)).setMovementMethod(LinkMovementMethod.getInstance());
02443                                                         }
02444                                                         else
02445                                                         {
02446                                                                 updateState(previousState);
02447                                                                 mToast.makeText(getActivity(), String.format("Exporting map failed!"), mToast.LENGTH_LONG).show();
02448                                                         }
02449                                                         mExportProgressDialog.dismiss();
02450                                                 }
02451                                                 else
02452                                                 {
02453                                                         mProgressDialog.dismiss();
02454                                                         mToast.makeText(getActivity(), String.format("Export canceled"), mToast.LENGTH_LONG).show();
02455                                                         updateState(previousState);
02456                                                 }
02457                                         }
02458                                 });
02459                         } 
02460                 });
02461                 exportThread.start();
02462         }
02463         
02464         private void saveDatabase(String fileName)
02465         {
02466                 final String newDatabasePath = mWorkingDirectory + fileName + ".db";
02467                 final String newDatabasePathHuman = mWorkingDirectoryHuman + fileName + ".db";
02468                 mProgressDialog.setTitle("Saving");
02469                 if(mOpenedDatabasePath.equals(newDatabasePath))
02470                 {
02471                         mProgressDialog.setMessage(String.format("Please wait while updating \"%s\"...", newDatabasePathHuman));
02472                 }
02473                 else
02474                 {
02475                         mProgressDialog.setMessage(String.format("Please wait while saving \"%s\"...", newDatabasePathHuman));
02476                 }
02477                 mProgressDialog.show();
02478                 final State previousState = mState;
02479                 updateState(State.STATE_PROCESSING);
02480                 Thread saveThread = new Thread(new Runnable() {
02481                         public void run() {
02482                                 RTABMapLib.save(newDatabasePath); // save
02483                                 runOnUiThread(new Runnable() {
02484                                         public void run() {
02485                                                 String msg;
02486                                                 if(mOpenedDatabasePath.equals(newDatabasePath))
02487                                                 {
02488                                                         msg = String.format("Database \"%s\" updated.", newDatabasePathHuman);  
02489                                                 }
02490                                                 else
02491                                                 {
02492                                                         msg = String.format("Database saved to \"%s\".", newDatabasePathHuman); 
02493                                                 }
02494                                                 
02495                                                 // build notification
02496                                                 Intent intent = new Intent(getActivity(), RTABMapActivity.class);
02497                                                 // use System.currentTimeMillis() to have a unique ID for the pending intent
02498                                                 PendingIntent pIntent = PendingIntent.getActivity(getActivity(), (int) System.currentTimeMillis(), intent, 0);
02499                                                 SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(getActivity());
02500                                                 boolean notifySound = sharedPref.getBoolean(getString(R.string.pref_key_notification_sound), Boolean.parseBoolean(getString(R.string.pref_default_notification_sound)));
02501                                                 Notification n  = new Notification.Builder(getActivity())
02502                                                 .setContentTitle(getString(R.string.app_name))
02503                                                 .setContentText(msg)
02504                                                 .setSmallIcon(R.drawable.ic_launcher)
02505                                                 .setContentIntent(pIntent)
02506                                                 .setDefaults(notifySound?Notification.DEFAULT_SOUND:0)
02507                                                 .setAutoCancel(true).build();
02508                                                 
02509                                                 NotificationManager notificationManager = 
02510                                                                 (NotificationManager) getSystemService(NOTIFICATION_SERVICE);
02511 
02512                                                 notificationManager.notify(0, n);
02513                                                 
02514                                                 final File f = new File(newDatabasePath);
02515                                                 final int fileSizeMB = (int)f.length()/(1024 * 1024);
02516                                                 
02517                                                 new AlertDialog.Builder(getActivity())
02518                                                 .setTitle("Database saved!")
02519                                                 .setMessage(String.format("Database \"%s\" (%d MB) successfully saved on the SD-CARD! Share it?", newDatabasePathHuman, fileSizeMB))
02520                                                 .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
02521                                                         public void onClick(DialogInterface dialog, int which) {
02522                                                                 // Send to...
02523                                                                 Intent shareIntent = new Intent();
02524                                                                 shareIntent.setAction(Intent.ACTION_SEND);
02525                                                                 shareIntent.putExtra(Intent.EXTRA_STREAM, Uri.fromFile(f));
02526                                                                 shareIntent.setType("application/octet-stream");
02527                                                                 startActivity(Intent.createChooser(shareIntent, "Sharing..."));
02528                                                                 
02529                                                                 resetNoTouchTimer(true);
02530                                                                 if(!mItemDataRecorderMode.isChecked())
02531                                                                 {
02532                                                                         mOpenedDatabasePath = newDatabasePath;
02533                                                                 }
02534                                                                 mProgressDialog.dismiss();
02535                                                                 updateState(previousState);
02536                                                         }
02537                                                 })
02538                                                 .setNegativeButton("No", new DialogInterface.OnClickListener() {
02539                                                         public void onClick(DialogInterface dialog, int which) {
02540                                                                 resetNoTouchTimer(true);
02541                                                                 if(!mItemDataRecorderMode.isChecked())
02542                                                                 {
02543                                                                         mOpenedDatabasePath = newDatabasePath;
02544                                                                 }
02545                                                                 mProgressDialog.dismiss();
02546                                                                 updateState(previousState);
02547                                                         }
02548                                                 })
02549                                                 .show();
02550                                         }
02551                                 });
02552                         } 
02553                 });
02554                 saveThread.start();
02555         }
02556         
02557         private void saveOnDevice()
02558         {
02559                 AlertDialog.Builder builder = new AlertDialog.Builder(this);
02560                 builder.setTitle("Model Name:");
02561                 final EditText input = new EditText(this);
02562                 input.setInputType(InputType.TYPE_CLASS_TEXT);        
02563                 builder.setView(input);
02564                 if(mOpenedDatabasePath.isEmpty())
02565                 {
02566                         String timeStamp = new SimpleDateFormat("yyMMdd-HHmmss").format(mDateOnPause);
02567                         input.setText(timeStamp);
02568                 }
02569                 else
02570                 {
02571                         File f = new File(mOpenedDatabasePath);
02572                         String name = f.getName();
02573                         input.setText(name.substring(0,name.lastIndexOf(".")));
02574                 }
02575                 input.setImeOptions(EditorInfo.IME_FLAG_NO_EXTRACT_UI);
02576                 input.setSelectAllOnFocus(true);
02577                 input.selectAll();
02578                 builder.setCancelable(false);
02579                 builder.setNegativeButton("Cancel", new DialogInterface.OnClickListener() {
02580                         @Override
02581                         public void onClick(DialogInterface dialog, int which)
02582                         {
02583                                 dialog.dismiss();
02584                                 resetNoTouchTimer(true);
02585                         }
02586                 });
02587                 builder.setPositiveButton("Ok", new DialogInterface.OnClickListener() {
02588                         @Override
02589                         public void onClick(DialogInterface dialog, int which)
02590                         {
02591                                 final String fileName = input.getText().toString();    
02592                                 dialog.dismiss();
02593                                 if(!fileName.isEmpty())
02594                                 {
02595                                         File newFile = new File(mWorkingDirectory + RTABMAP_EXPORT_DIR + fileName + ".zip");
02596                                         if(newFile.exists())
02597                                         {
02598                                                 new AlertDialog.Builder(getActivity())
02599                                                 .setTitle("File Already Exists")
02600                                                 .setMessage("Do you want to overwrite the existing file?")
02601                                                 .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
02602                                                         public void onClick(DialogInterface dialog, int which) {
02603                                                                 writeExportedFiles(fileName);
02604                                                         }
02605                                                 })
02606                                                 .setNegativeButton("No", new DialogInterface.OnClickListener() {
02607                                                         public void onClick(DialogInterface dialog, int which) {
02608                                                                 saveOnDevice();
02609                                                         }
02610                                                 })
02611                                                 .show();
02612                                         }
02613                                         else
02614                                         {
02615                                                 writeExportedFiles(fileName);
02616                                         }
02617                                 }
02618                         }
02619                 });
02620                 AlertDialog alertToShow = builder.create();
02621                 alertToShow.getWindow().setSoftInputMode(WindowManager.LayoutParams.SOFT_INPUT_STATE_VISIBLE);
02622                 alertToShow.show();
02623         }
02624         
02625         private void writeExportedFiles(final String fileName)
02626         {               
02627                 Log.i(TAG, String.format("Write exported mesh to \"%s\"", fileName));
02628                 
02629                 mProgressDialog.setTitle("Saving to sd-card");
02630                 mProgressDialog.setMessage(String.format("Compressing the files..."));
02631                 mProgressDialog.show();
02632                 
02633                 Thread workingThread = new Thread(new Runnable() {
02634                         public void run() {
02635                                 boolean success = false;
02636                                 
02637                                 File tmpDir = new File(mWorkingDirectory + RTABMAP_TMP_DIR);
02638                                 tmpDir.mkdirs();
02639                                 String[] fileNames = Util.loadFileList(mWorkingDirectory + RTABMAP_TMP_DIR, false);
02640                                 if(!DISABLE_LOG) Log.i(TAG, String.format("Deleting %d files in \"%s\"", fileNames.length, mWorkingDirectory + RTABMAP_TMP_DIR));
02641                                 for(int i=0; i<fileNames.length; ++i)
02642                                 {
02643                                         File f = new File(mWorkingDirectory + RTABMAP_TMP_DIR + "/" + fileNames[i]);
02644                                         if(f.delete())
02645                                         {
02646                                                 if(!DISABLE_LOG) Log.i(TAG, String.format("Deleted \"%s\"", f.getPath()));
02647                                         }
02648                                         else
02649                                         {
02650                                                 if(!DISABLE_LOG) Log.i(TAG, String.format("Failed deleting \"%s\"", f.getPath()));
02651                                         }
02652                                 }
02653                                 File exportDir = new File(mWorkingDirectory + RTABMAP_EXPORT_DIR);
02654                                 exportDir.mkdirs();
02655                                 
02656                                 final String pathHuman = mWorkingDirectoryHuman + RTABMAP_EXPORT_DIR + fileName + ".zip";
02657                                 final String zipOutput = mWorkingDirectory+RTABMAP_EXPORT_DIR+fileName+".zip";
02658                                 if(RTABMapLib.writeExportedMesh(mWorkingDirectory + RTABMAP_TMP_DIR, RTABMAP_TMP_FILENAME))
02659                                 {                                                       
02660                                         fileNames = Util.loadFileList(mWorkingDirectory + RTABMAP_TMP_DIR, false);
02661                                         if(fileNames.length > 0)
02662                                         {
02663                                                 String[] filesToZip = new String[fileNames.length];
02664                                                 for(int i=0; i<fileNames.length; ++i)
02665                                                 {
02666                                                         filesToZip[i] = mWorkingDirectory + RTABMAP_TMP_DIR + "/" + fileNames[i];
02667                                                 }
02668                         
02669                                                 File toZIPFile = new File(zipOutput);
02670                                                 toZIPFile.delete();                     
02671                                                 
02672                                                 try
02673                                                 {
02674                                                         Util.zip(filesToZip, zipOutput);
02675                                                         success = true;
02676                                                 }
02677                                                 catch(IOException e)
02678                                                 {
02679                                                         final String msg = e.getMessage();
02680                                                         runOnUiThread(new Runnable() {
02681                                                                 public void run() {
02682                                                                         mToast.makeText(getActivity(), String.format("Exporting mesh \"%s\" failed! Error=%s", pathHuman, msg), mToast.LENGTH_LONG).show();
02683                                                                 }
02684                                                         });
02685                                                 }
02686                                         }
02687                                 }
02688                                 
02689                                 if(success)
02690                                 {
02691                                         runOnUiThread(new Runnable() {
02692                                                 public void run() {
02693                                                         mProgressDialog.dismiss();
02694                                                         
02695                                                         final File f = new File(zipOutput);
02696                                                         final int fileSizeMB = (int)f.length()/(1024 * 1024);
02697                                                         
02698                                                         new AlertDialog.Builder(getActivity())
02699                                                         .setTitle("Database saved!")
02700                                                         .setMessage(String.format("Mesh \"%s\" (%d MB) successfully exported on the SD-CARD! Share it?", pathHuman, fileSizeMB))
02701                                                         .setPositiveButton("Yes", new DialogInterface.OnClickListener() {
02702                                                                 public void onClick(DialogInterface dialog, int which) {
02703                                                                         // Send to...
02704                                                                         Intent shareIntent = new Intent();
02705                                                                         shareIntent.setAction(Intent.ACTION_SEND);
02706                                                                         shareIntent.putExtra(Intent.EXTRA_STREAM, Uri.fromFile(f));
02707                                                                         shareIntent.setType("application/zip");
02708                                                                         startActivity(Intent.createChooser(shareIntent, "Sharing..."));
02709                                                                                                                                 
02710                                                                         resetNoTouchTimer(true);
02711                                                                 }
02712                                                         })
02713                                                         .setNegativeButton("No", new DialogInterface.OnClickListener() {
02714                                                                 public void onClick(DialogInterface dialog, int which) {
02715                                                                         resetNoTouchTimer(true);
02716                                                                 }
02717                                                         })
02718                                                         .show();
02719                                                 }
02720                                         });
02721                                 }
02722                                 else
02723                                 {
02724                                         runOnUiThread(new Runnable() {
02725                                                 public void run() {
02726                                                         mProgressDialog.dismiss();
02727                                                         mToast.makeText(getActivity(), String.format("Exporting mesh \"%s\" failed! No files found in tmp directory!? Last export may have failed or have been canceled.", pathHuman), mToast.LENGTH_LONG).show();
02728                                                         resetNoTouchTimer(true);
02729                                                 }
02730                                         });
02731                                 }
02732                         }
02733                 });
02734                 workingThread.start();
02735         }
02736         
02737         private void openDatabase(final String fileName, final boolean optimize)
02738         {
02739                 mOpenedDatabasePath = mWorkingDirectory + fileName;
02740                 
02741                 Log.i(TAG, "Open database " + mOpenedDatabasePath);
02742                 
02743                 SharedPreferences sharedPref = PreferenceManager.getDefaultSharedPreferences(getActivity());
02744                 final boolean databaseInMemory = sharedPref.getBoolean(getString(R.string.pref_key_db_in_memory), Boolean.parseBoolean(getString(R.string.pref_default_db_in_memory)));         
02745                 
02746                 
02747                 mProgressDialog.setTitle("Loading");
02748                 mProgressDialog.setMessage(String.format("Opening database \"%s\"...", fileName));
02749                 mProgressDialog.show();
02750                 updateState(State.STATE_PROCESSING);
02751                 
02752                 Thread openThread = new Thread(new Runnable() {
02753                         public void run() {
02754                         
02755                                 final String tmpDatabase = mWorkingDirectory+RTABMAP_TMP_DB;                            
02756                                 final int status = RTABMapLib.openDatabase2(mOpenedDatabasePath, tmpDatabase, databaseInMemory, optimize);
02757                                 
02758                                 runOnUiThread(new Runnable() {
02759                                         public void run() {
02760                                                 if(status == -1)
02761                                                 {
02762                                                         updateState(State.STATE_IDLE);
02763                                                         mProgressDialog.dismiss();
02764                                                         new AlertDialog.Builder(getActivity())
02765                                                         .setCancelable(false)
02766                                                         .setTitle("Error")
02767                                                         .setMessage("The map is loaded but optimization of the map's graph has "
02768                                                                         + "failed, so the map cannot be shown. Change the Graph Optimizer approach used"
02769                                                                         + " or enable/disable if the graph is optimized from graph "
02770                                                                         + "end in \"Settings -> Mapping...\" and try opening again.")
02771                                                         .setPositiveButton("Open Settings", new DialogInterface.OnClickListener() {
02772                                                                 public void onClick(DialogInterface dialog, int which) {
02773                                                                         Intent intent = new Intent(getActivity(), SettingsActivity.class);
02774                                                                         startActivity(intent);
02775                                                                         mBlockBack = true;
02776                                                                 }
02777                                                         })
02778                                                         .setNegativeButton("Close", new DialogInterface.OnClickListener() {
02779                                                                 public void onClick(DialogInterface dialog, int which) {
02780                                                                 }
02781                                                         })
02782                                                         .show();
02783                                                 }
02784                                                 else if(status == -2)
02785                                                 {
02786                                                         updateState(State.STATE_IDLE);
02787                                                         mProgressDialog.dismiss();
02788                                                         new AlertDialog.Builder(getActivity())
02789                                                         .setCancelable(false)
02790                                                         .setTitle("Error")
02791                                                         .setMessage("Failed to open database: Out of memory! Try "
02792                                                                         + "again after lowering Point Cloud Density in Settings.")
02793                                                         .setPositiveButton("Open Settings", new DialogInterface.OnClickListener() {
02794                                                                 public void onClick(DialogInterface dialog, int which) {
02795                                                                         Intent intent = new Intent(getActivity(), SettingsActivity.class);
02796                                                                         startActivity(intent);
02797                                                                         mBlockBack = true;
02798                                                                 }
02799                                                         })
02800                                                         .setNegativeButton("Close", new DialogInterface.OnClickListener() {
02801                                                                 public void onClick(DialogInterface dialog, int which) {
02802                                                                 }
02803                                                         })
02804                                                         .show();
02805                                                 }
02806                                                 else
02807                                                 {
02808                                                         if(status >= 1 && status<=3)
02809                                                         {
02810                                                                 mProgressDialog.dismiss();
02811                                                                 resetNoTouchTimer(true);
02812                                                                 updateState(State.STATE_VISUALIZING);
02813                                                                 mToast.makeText(getActivity(), String.format("Database loaded!"), mToast.LENGTH_LONG).show();
02814                                                         }
02815                                                         else if(!mItemTrajectoryMode.isChecked())
02816                                                         {
02817                                                                 if(mButtonCameraView.getSelectedItemPosition() == 0)
02818                                                                 {
02819                                                                         setCamera(2);
02820                                                                 }
02821                                                                 // creating meshes...
02822                                                                 updateState(State.STATE_IDLE);
02823                                                                 mProgressDialog.setTitle("Loading");
02824                                                                 mProgressDialog.setMessage(String.format("Database \"%s\" loaded. Please wait while rendering point clouds and meshes...", fileName));
02825                                                         }
02826                                                         
02827                                                 }
02828                                         }
02829                                 });
02830                         } 
02831                 });
02832                 openThread.start();     
02833         }
02834         
02835         public void copy(File src, File dst) throws IOException {
02836             InputStream in = new FileInputStream(src);
02837             OutputStream out = new FileOutputStream(dst);
02838 
02839             // Transfer bytes from in to out
02840             byte[] buf = new byte[1024];
02841             int len;
02842             while ((len = in.read(buf)) > 0) {
02843                 out.write(buf, 0, len);
02844             }
02845             in.close();
02846             out.close();
02847         }
02848                 
02849         private void shareToSketchfab()
02850         {
02851                 Intent intent = new Intent(getActivity(), SketchfabActivity.class);
02852                 
02853                 intent.putExtra(RTABMAP_AUTH_TOKEN_KEY, mAuthToken);
02854                 intent.putExtra(RTABMAP_WORKING_DIR_KEY, mWorkingDirectory);
02855                 
02856                 if(mOpenedDatabasePath.isEmpty())
02857                 {
02858                         intent.putExtra(RTABMAP_FILENAME_KEY, new SimpleDateFormat("yyMMdd-HHmmss").format(mDateOnPause));
02859                 }
02860                 else
02861                 {
02862                         File f = new File(mOpenedDatabasePath);
02863                         String name = f.getName();
02864                         intent.putExtra(RTABMAP_FILENAME_KEY, name.substring(0,name.lastIndexOf(".")));
02865                 }
02866                 
02867                 startActivityForResult(intent, SKETCHFAB_ACTIVITY_CODE);
02868                 mBlockBack = true;
02869         }
02870 }


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