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