MainActivity.java
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2013 OSRF.
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License"); you may not
00005  * use this file except in compliance with the License. You may obtain a copy of
00006  * the License at
00007  *
00008  * http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
00012  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
00013  * License for the specific language governing permissions and limitations under
00014  * the License.
00015  */
00016 
00017 package com.github.rosjava.android_apps.map_manager;
00018 
00019 import android.annotation.SuppressLint;
00020 import android.app.AlertDialog;
00021 import android.app.Dialog;
00022 import android.app.ProgressDialog;
00023 import android.content.DialogInterface;
00024 import android.os.Bundle;
00025 import android.util.Log;
00026 import android.view.Display;
00027 import android.view.KeyEvent;
00028 import android.view.Menu;
00029 import android.view.MenuItem;
00030 import android.view.MotionEvent;
00031 import android.view.View;
00032 import android.view.View.OnLongClickListener;
00033 import android.view.View.OnTouchListener;
00034 import android.view.WindowManager;
00035 import android.widget.Button;
00036 import android.widget.EditText;
00037 import android.widget.ListView;
00038 
00039 import com.github.rosjava.android_remocons.common_tools.apps.RosAppActivity;
00040 import com.google.common.collect.Lists;
00041 
00042 import org.ros.address.InetAddressFactory;
00043 import org.ros.android.view.visualization.VisualizationView;
00044 import org.ros.android.view.visualization.layer.CameraControlLayer;
00045 import org.ros.android.view.visualization.layer.CameraControlListener;
00046 import org.ros.android.view.visualization.layer.Layer;
00047 import org.ros.android.view.visualization.layer.OccupancyGridLayer;
00048 import org.ros.exception.RemoteException;
00049 import org.ros.namespace.NameResolver;
00050 import org.ros.node.NodeConfiguration;
00051 import org.ros.node.NodeMainExecutor;
00052 import org.ros.node.service.ServiceResponseListener;
00053 
00054 import java.text.DateFormat;
00055 import java.util.ArrayList;
00056 import java.util.Date;
00057 import java.util.List;
00058 
00059 import world_canvas_msgs.DeleteMapResponse;
00060 import world_canvas_msgs.ListMapsResponse;
00061 import world_canvas_msgs.MapListEntry;
00062 import world_canvas_msgs.PublishMapResponse;
00063 import world_canvas_msgs.RenameMapResponse;
00064 
00068 @SuppressLint("NewApi")
00069 public class MainActivity extends RosAppActivity {
00070 
00071         private static final int NAME_MAP_DIALOG_ID = 0;
00072 
00073         private NodeConfiguration nodeConfiguration;
00074         private NodeMainExecutor nodeMainExecutor;
00075 
00076         private VisualizationView mapView;
00077         private Button backButton;
00078         private Button renameButton;
00079         private ListView mapListView;
00080         private ArrayList<MapListEntry> mapList = new ArrayList<MapListEntry>();
00081         public OnTouchListener gestureListener;
00082         public OnLongClickListener longClickListener;
00083         private int radioFocus = 0;
00084         private int viewPosition = -1;
00085         private int targetPosition;
00086         private boolean startMapManager = true;
00087         private boolean showDeleteDialog = false;
00088         private boolean visibleMapView = true;
00089         private ProgressDialog waitingDialog;
00090         private AlertDialog errorDialog;
00091     private CameraControlLayer cameraControlLayer;
00092         private OccupancyGridLayer occupancyGridLayer;
00093 
00094         public MainActivity() {
00095                 // The RosActivity constructor configures the notification title and
00096                 // ticker
00097                 // messages.
00098                 super("map manager", "map manager");
00099         }
00100 
00101         @SuppressWarnings("unchecked")
00102         @Override
00103         public void onCreate(Bundle savedInstanceState) {
00104 
00105                 String defaultRobotName = getString(R.string.default_robot);
00106                 String defaultAppName = getString(R.string.default_app);
00107         setDefaultMasterName(defaultRobotName);
00108                 setDefaultAppName(defaultAppName);
00109                 setDashboardResource(R.id.top_bar);
00110                 setMainWindowResource(R.layout.main);
00111                 super.onCreate(savedInstanceState);
00112 
00113                 WindowManager windowManager = getWindowManager();
00114                 final Display display = windowManager.getDefaultDisplay();
00115 
00116                 mapListView = (ListView) findViewById(R.id.map_list);
00117                 mapView = (VisualizationView) findViewById(R.id.map_view);
00118                 backButton = (Button) findViewById(R.id.back_button);
00119                 renameButton = (Button) findViewById(R.id.rename_button);
00120         cameraControlLayer = new CameraControlLayer();
00121         mapView.onCreate(Lists.<Layer>newArrayList(cameraControlLayer));
00122 
00123                 backButton.setOnClickListener(new View.OnClickListener() {
00124                         @Override
00125                         public void onClick(View view) {
00126                                 onBackPressed();
00127                         }
00128                 });
00129 
00130                 renameButton.setOnClickListener(new View.OnClickListener() {
00131                         @Override
00132                         public void onClick(View view) {
00133                                 if (radioFocus != -1) {
00134                                         targetPosition = radioFocus;
00135                                         showDialog(NAME_MAP_DIALOG_ID);
00136                                 }
00137                         }
00138                 });
00139 
00140                 gestureListener = new View.OnTouchListener() {
00141                         private int padding = 0;
00142                         private int initialX = 0;
00143                         private int currentX = 0;
00144 
00145                         public boolean onTouch(View v, MotionEvent event) {
00146                                 if (!showDeleteDialog) {
00147 
00148                                         if (event.getAction() == MotionEvent.ACTION_DOWN) {
00149                                                 padding = 0;
00150                                                 initialX = (int) event.getX();
00151                                                 currentX = (int) event.getX();
00152                                         }
00153                                         if (event.getAction() == MotionEvent.ACTION_MOVE) {
00154                                                 currentX = (int) event.getX();
00155                                                 padding = currentX - initialX;
00156                                         }
00157 
00158                                         if (event.getAction() == MotionEvent.ACTION_UP
00159                                                         || event.getAction() == MotionEvent.ACTION_CANCEL) {
00160                                                 padding = 0;
00161                                                 initialX = 0;
00162                                                 currentX = 0;
00163                                         }
00164 
00165                                         if (Math.abs(padding) > display.getWidth() * 0.2f) {
00166                                                 deleteMap(v.getId());
00167                                                 v.setAlpha(0);
00168                                                 showDeleteDialog = true;
00169                                                 return true;
00170                                         }
00171                                         v.setPadding(padding, 0, -padding, 0);
00172                                         float alpha = 1 - Math.abs(padding)
00173                                                         / (display.getWidth() * 0.2f);
00174                                         if (alpha > 0) {
00175                                                 v.setAlpha(alpha);
00176 
00177                                         } else {
00178                                                 v.setAlpha(0);
00179                                         }
00180                                 }
00181                                 return false;
00182                         }
00183                 };
00184                 
00185                 longClickListener = new View.OnLongClickListener() {
00186 
00187                         @Override
00188                         public boolean onLongClick(View v) {
00189                                 targetPosition = v.getId();
00190                                 showDialog(NAME_MAP_DIALOG_ID);
00191                                 return false;
00192                         }
00193                         
00194                 };
00195 
00196 
00197         mapView.getCamera().jumpToFrame((String) params.get("robot_frame", getString(R.string.robot_frame)));
00198         }
00199 
00200         @Override
00201         protected void init(NodeMainExecutor nodeMainExecutor) {
00202 
00203                 super.init(nodeMainExecutor);
00204 
00205                 this.nodeMainExecutor = nodeMainExecutor;
00206                 nodeConfiguration = NodeConfiguration.newPublic(InetAddressFactory
00207                                 .newNonLoopback().getHostAddress(), getMasterUri());
00208 
00209         NameResolver appNameSpace = getMasterNameSpace();
00210         String mapTopic = remaps.get(getString(R.string.map_topic));
00211 
00212         mapView.init(nodeMainExecutor);
00213         cameraControlLayer.addListener(new CameraControlListener() {
00214             @Override
00215             public void onZoom(float focusX, float focusY, float factor) {}
00216             @Override
00217             public void onDoubleTap(float x, float y) {}
00218             @Override
00219             public void onTranslate(float distanceX, float distanceY) {}
00220             @Override
00221             public void onRotate(float focusX, float focusY, double deltaAngle) {}
00222 
00223         });
00224         occupancyGridLayer = new OccupancyGridLayer(appNameSpace.resolve(mapTopic).toString());
00225         mapView.addLayer(occupancyGridLayer);
00226 
00227                 nodeMainExecutor.execute(mapView, nodeConfiguration.setNodeName("android/map_view"));
00228                 updateMapList();
00229         }
00230 
00231         protected void updateMapView(int position) {
00232                 radioFocus = position;
00233                 updateMapView(MainActivity.this.mapList.get(position));
00234         }
00235 
00236         private void updateMapView(MapListEntry map) {
00237 
00238                 MapManager mapManager = new MapManager();
00239         mapManager.setNameResolver(getMasterNameSpace());
00240                 mapManager.setFunction("publish");
00241                 mapManager.setMapId(map.getMapId());
00242                 safeShowWaitingDialog("Loading...");
00243 
00244                 mapManager.setPublishService(new ServiceResponseListener<PublishMapResponse>() {
00245                                         @Override
00246                                         public void onFailure(RemoteException e) {
00247                                                 e.printStackTrace();
00248                                                 safeDismissWaitingDialog();
00249                                                 safeShowErrorDialog("Error loading map: " + e.toString());
00250                                         }
00251                                         @Override
00252                                         public void onSuccess(PublishMapResponse message) {
00253                                                 safeDismissWaitingDialog();
00254                         // disabling temporarily until testing
00255                         // this api got deprecated
00256                         // see https://github.com/rosjava/android_apps/issues/42
00257                         // if (!visibleMapView) {
00258                                                 //      mapView.addLayer(occupancyGridLayer);
00259                                                 //      visibleMapView = true;
00260                                                 // }
00261                                         }
00262                                 });
00263 
00264                 nodeMainExecutor.execute(mapManager,
00265                                 nodeConfiguration.setNodeName("android/publish_map"));
00266 
00267         }
00268 
00269         private void updateMapListGui(final List<MapListEntry> list) {
00270 
00271                 final ArrayList<MapListData> availableMapNames = new ArrayList<MapListData>();
00272                 for (int i = 0; i < list.size(); i++) {
00273                         String displayString;
00274                         String name = list.get(i).getName();
00275                         Date creationDate = new Date(list.get(i).getDate() * 1000);
00276                         String dateTime = DateFormat.getDateTimeInstance(DateFormat.MEDIUM,
00277                                         DateFormat.SHORT).format(creationDate);
00278                         if (name != null && !name.equals("")) {
00279                                 displayString = name + " " + dateTime;
00280                         } else {
00281                                 displayString = dateTime;
00282                         }
00283                         MapListData mapListData = new MapListData();
00284                         mapListData.setText(displayString);
00285                         if (i == radioFocus) {
00286                                 mapListData.setChecked(true);
00287                         } else
00288                                 mapListData.setChecked(false);
00289                         mapListData.setId(i);
00290                         availableMapNames.add(mapListData);
00291                 }
00292 
00293                 mapList = (ArrayList<MapListEntry>) list;
00294 
00295                 if (startMapManager) {
00296                         startMapManager = false;
00297                         updateMapView(0);
00298                 }
00299 
00300                 runOnUiThread(new Runnable() {
00301                         @Override
00302                         public void run() {
00303                                 final MapListArrayAdapter ad = new MapListArrayAdapter(
00304                                                 MainActivity.this, 0, availableMapNames,
00305                                                 gestureListener,longClickListener);
00306                                 mapListView.setAdapter(ad);
00307                                 if (viewPosition != -1) {
00308                                         mapListView.setSelection(viewPosition);
00309                                 }
00310 
00311                         }
00312                 });
00313         }
00314 
00315         private void updateMapList() {
00316 
00317                 MapManager mapManager = new MapManager();
00318         mapManager.setNameResolver(getMasterNameSpace());
00319                 mapManager.setFunction("list");
00320                 safeShowWaitingDialog("Waiting for maps...");
00321 
00322                 mapManager.setListService(new ServiceResponseListener<ListMapsResponse>() {
00323                                         @Override
00324                                         public void onSuccess(ListMapsResponse message) {
00325                                                 Log.i("MapManager", "readAvailableMapList() Success");
00326                                                 safeDismissWaitingDialog();
00327                                                 updateMapListGui(message.getMapList());
00328                                         }
00329 
00330                                         @Override
00331                                         public void onFailure(RemoteException arg0) {
00332                                                 Log.i("MapManager", "readAvailableMapList() Failure");
00333                                                 safeDismissWaitingDialog();
00334                                                 
00335                                         }
00336                                 });
00337 
00338                 nodeMainExecutor.execute(mapManager,
00339                                 nodeConfiguration.setNodeName("android/list_maps"));
00340 
00341         }
00342 
00343         public void deleteMap(int position) {
00344                 final String id = mapList.get(position).getMapId();
00345                 viewPosition = mapListView.getFirstVisiblePosition();
00346 
00347                 if (id == null) {
00348                         return;
00349                 }
00350                 final int radioFocusRelation;
00351                 if (position == radioFocus) {
00352                         radioFocusRelation = 0;
00353                 } else if (position < radioFocus) {
00354                         radioFocusRelation = 1;
00355                 } else
00356                         radioFocusRelation = -1;
00357 
00358                 AlertDialog.Builder dialog = new AlertDialog.Builder(this);
00359                 dialog.setTitle("Are You Sure?");
00360                 dialog.setMessage("Are you sure you want to delete this map?");
00361                 dialog.setPositiveButton("Yes", new DialogInterface.OnClickListener() {
00362                         @Override
00363                         public void onClick(DialogInterface dlog, int i) {
00364                                 dlog.dismiss();
00365                                 safeShowWaitingDialog("Deleting...");
00366                                 try {
00367                                         MapManager mapManager = new MapManager();
00368                     mapManager.setNameResolver(getMasterNameSpace());
00369                                         mapManager.setFunction("delete");
00370                                         mapManager.setMapId(id);
00371 
00372                                         mapManager.setDeleteService(new ServiceResponseListener<DeleteMapResponse>() {
00373 
00374                                                                 @Override
00375                                                                 public void onFailure(RemoteException e) {
00376                                                                         showDeleteDialog = false;
00377                                                                         e.printStackTrace();
00378 
00379                                                                 }
00380 
00381                                                                 @Override
00382                                                                 public void onSuccess(DeleteMapResponse arg0) {
00383 
00384                                                                         if (viewPosition != 0) {
00385                                                                                 viewPosition += 1;
00386                                                                         }
00387                                                                         switch (radioFocusRelation) {
00388                                                                         case 0:
00389                                         // disabling temporarily until testing
00390                                         // this api got deprecated
00391                                         // see https://github.com/rosjava/android_apps/issues/42
00392                                                                                 //mapView.hideLayer(occupancyGridLayer);
00393                                                                                 //visibleMapView = false;
00394                                                                                 radioFocus = -1;
00395                                                                                 break;
00396                                                                         case 1:
00397                                                                                 radioFocus -= 1;
00398                                                                                 break;
00399                                                                         }
00400                                                                         showDeleteDialog = false;
00401 
00402                                                                         MainActivity.this
00403                                                                                         .runOnUiThread(new Runnable() {
00404                                                                                                 public void run() {
00405                                                                                                         safeDismissWaitingDialog();
00406                                                                                                         updateMapList();
00407                                                                                                 }
00408                                                                                         });
00409                                                                 }
00410                                                         });
00411 
00412                                         nodeMainExecutor.execute(mapManager,
00413                                                         nodeConfiguration.setNodeName("android/delete_map"));
00414 
00415                                 } catch (Exception e) {
00416                                         e.printStackTrace();
00417                                         safeShowErrorDialog("Error during map delete: "
00418                                                         + e.toString());
00419                                 }
00420                         }
00421                 });
00422 
00423                 dialog.setNegativeButton("No", new DialogInterface.OnClickListener() {
00424                         @Override
00425                         public void onClick(DialogInterface dlog, int i) {
00426                                 if (viewPosition != 0) {
00427                                         viewPosition += 1;
00428                                 }
00429                                 showDeleteDialog = false;
00430                                 updateMapList();
00431                                 dlog.dismiss();
00432                         }
00433                 });
00434                 dialog.show();
00435         }
00436 
00437         @Override
00438         protected Dialog onCreateDialog(int id) {
00439                 Dialog dialog;
00440                 Button button;
00441                 switch (id) {
00442                 case NAME_MAP_DIALOG_ID:
00443                         viewPosition = mapListView.getFirstVisiblePosition();
00444                         dialog = new Dialog(this);
00445                         dialog.setContentView(R.layout.name_map_dialog);
00446                         dialog.setTitle("Rename Map");
00447 
00448                         final String targetMapId = mapList.get(targetPosition).getMapId();
00449                         final EditText nameField = (EditText) dialog
00450                                         .findViewById(R.id.name_editor);
00451                         nameField.setText(mapList.get(targetPosition).getName());
00452                         nameField.setOnKeyListener(new View.OnKeyListener() {
00453                                 @Override
00454                                 public boolean onKey(final View view, int keyCode,
00455                                                 KeyEvent event) {
00456                                         if (event.getAction() == KeyEvent.ACTION_DOWN
00457                                                         && keyCode == KeyEvent.KEYCODE_ENTER) {
00458                                                 String newName = nameField.getText().toString();
00459                                                 if (newName != null && newName.length() > 0) {
00460                                                         safeShowWaitingDialog("Waiting for rename...");
00461                                                         try {
00462                                                                 MapManager mapManager = new MapManager();
00463                                 mapManager.setNameResolver(getMasterNameSpace());
00464                                                                 mapManager.setFunction("rename");
00465                                                                 mapManager.setMapId(targetMapId);
00466                                                                 mapManager.setMapName(newName);
00467 
00468                                                                 mapManager.setRenameService(
00469                                         new ServiceResponseListener<RenameMapResponse>() {
00470 
00471                                                                                         @Override
00472                                                                                         public void onFailure(
00473                                                                                                         RemoteException e) {
00474                                                                                                 e.printStackTrace();
00475                                                                                                 safeShowErrorDialog("Error during rename: "
00476                                                                                                                 + e.toString());
00477                                                                                         }
00478 
00479                                                                                         @Override
00480                                                                                         public void onSuccess(
00481                                                                                                         RenameMapResponse arg0) {
00482                                                                                                 MainActivity.this
00483                                                                                                                 .runOnUiThread(new Runnable() {
00484                                                                                                                         public void run() {
00485                                                                                                                                 safeDismissWaitingDialog();
00486                                                                                                                                 updateMapList();
00487                                                                                                                         }
00488                                                                                                                 });
00489                                                                                         }
00490                                                                                 });
00491                                                                 nodeMainExecutor.execute(mapManager,
00492                                                                                 nodeConfiguration
00493                                                                                                 .setNodeName("android/rename_map"));
00494 
00495                                                         } catch (Exception e) {
00496                                                                 e.printStackTrace();
00497                                                                 safeShowErrorDialog("Error during rename: "
00498                                                                                 + e.toString());
00499                                                         }
00500                                                 }
00501                                                 removeDialog(NAME_MAP_DIALOG_ID);
00502                                                 return true;
00503                                         } else {
00504                                                 return false;
00505                                         }
00506                                 }
00507                         });
00508 
00509                         button = (Button) dialog.findViewById(R.id.cancel_button);
00510                         button.setOnClickListener(new View.OnClickListener() {
00511                                 @Override
00512                                 public void onClick(View v) {
00513                                         removeDialog(NAME_MAP_DIALOG_ID);
00514                                 }
00515                         });
00516                         break;
00517                 default:
00518                         dialog = null;
00519                 }
00520                 return dialog;
00521         }
00522 
00523         private void safeShowWaitingDialog(final CharSequence message) {
00524                 runOnUiThread(new Runnable() {
00525                         @Override
00526                         public void run() {
00527                                 if (waitingDialog != null) {
00528                                         waitingDialog.dismiss();
00529                                         waitingDialog = null;
00530                                 }
00531                                 waitingDialog = ProgressDialog.show(MainActivity.this, "",
00532                                                 message, true);
00533                         }
00534                 });
00535         }
00536 
00537         private void safeDismissWaitingDialog() {
00538                 runOnUiThread(new Runnable() {
00539                         @Override
00540                         public void run() {
00541                                 if (waitingDialog != null) {
00542                                         waitingDialog.dismiss();
00543                                         waitingDialog = null;
00544                                 }
00545                         }
00546                 });
00547         }
00548 
00549         private void safeShowErrorDialog(final CharSequence message) {
00550                 runOnUiThread(new Runnable() {
00551                         @Override
00552                         public void run() {
00553                                 if (errorDialog != null) {
00554                                         errorDialog.dismiss();
00555                                         errorDialog = null;
00556                                 }
00557                                 if (waitingDialog != null) {
00558                                         waitingDialog.dismiss();
00559                                         waitingDialog = null;
00560                                 }
00561                                 AlertDialog.Builder dialog = new AlertDialog.Builder(
00562                                                 MainActivity.this);
00563                                 dialog.setTitle("Error");
00564                                 dialog.setMessage(message);
00565                                 dialog.setNeutralButton("Ok",
00566                                                 new DialogInterface.OnClickListener() {
00567                                                         @Override
00568                                                         public void onClick(DialogInterface dlog, int i) {
00569                                                                 dlog.dismiss();
00570                                                         }
00571                                                 });
00572                                 errorDialog = dialog.show();
00573                         }
00574                 });
00575         }
00576 
00577         private void safeDismissErrorDialog() {
00578                 runOnUiThread(new Runnable() {
00579                         @Override
00580                         public void run() {
00581                                 if (errorDialog != null) {
00582                                         errorDialog.dismiss();
00583                                         errorDialog = null;
00584                                 }
00585                         }
00586                 });
00587         }
00588 
00589         @Override
00590         public boolean onCreateOptionsMenu(Menu menu) {
00591                 menu.add(0, 0, 0, R.string.stop_app);
00592                 return super.onCreateOptionsMenu(menu);
00593         }
00594 
00595         @Override
00596         public boolean onOptionsItemSelected(MenuItem item) {
00597                 super.onOptionsItemSelected(item);
00598                 switch (item.getItemId()) {
00599                 case 0:
00600                         onDestroy();
00601                         break;
00602                 }
00603                 return true;
00604         }
00605 
00606 }


android_apps
Author(s): Daniel Stonier , Kazuto Murase
autogenerated on Thu Jun 6 2019 21:11:28