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.make_a_map;
00018 
00019 import android.app.AlertDialog;
00020 import android.app.Dialog;
00021 import android.app.ProgressDialog;
00022 import android.content.DialogInterface;
00023 import android.os.Bundle;
00024 import android.view.KeyEvent;
00025 import android.view.Menu;
00026 import android.view.MenuItem;
00027 import android.view.View;
00028 import android.view.ViewGroup;
00029 import android.widget.Button;
00030 import android.widget.EditText;
00031 import android.widget.ImageButton;
00032 import android.widget.Toast;
00033 
00034 import com.github.rosjava.android_remocons.common_tools.apps.RosAppActivity;
00035 import com.google.common.collect.Lists;
00036 
00037 import org.ros.address.InetAddressFactory;
00038 import org.ros.android.BitmapFromCompressedImage;
00039 import org.ros.android.view.RosImageView;
00040 import org.ros.android.view.VirtualJoystickView;
00041 import org.ros.android.view.visualization.VisualizationView;
00042 import org.ros.android.view.visualization.layer.CameraControlListener;
00043 import org.ros.android.view.visualization.layer.LaserScanLayer;
00044 import org.ros.android.view.visualization.layer.Layer;
00045 import org.ros.android.view.visualization.layer.OccupancyGridLayer;
00046 import org.ros.android.view.visualization.layer.RobotLayer;
00047 import org.ros.namespace.NameResolver;
00048 import org.ros.node.NodeConfiguration;
00049 import org.ros.node.NodeMainExecutor;
00050 
00051 import world_canvas_msgs.SaveMapResponse;
00052 
00056 public class MainActivity extends RosAppActivity {
00057 
00058     private static final int NAME_MAP_DIALOG_ID = 0;
00059 
00060         private RosImageView<sensor_msgs.CompressedImage> cameraView;
00061         private VirtualJoystickView virtualJoystickView;
00062         private VisualizationView mapView;
00063         private ViewGroup mainLayout;
00064         private ViewGroup sideLayout;
00065         private ImageButton refreshButton;
00066         private ImageButton saveButton;
00067         private Button backButton;
00068         private NodeMainExecutor nodeMainExecutor;
00069         private NodeConfiguration nodeConfiguration;
00070         private ProgressDialog waitingDialog;
00071         private AlertDialog notiDialog;
00072 
00073 
00074     private OccupancyGridLayer occupancyGridLayer = null;
00075     private LaserScanLayer laserScanLayer = null;
00076     private RobotLayer robotLayer = null;
00077 
00078         public MainActivity() {
00079                 // The RosActivity constructor configures the notification title and
00080                 // ticker
00081                 // messages.
00082                 super("Make a map", "Make a map");
00083 
00084         }
00085 
00086         @SuppressWarnings("unchecked")
00087         @Override
00088         public void onCreate(Bundle savedInstanceState) {
00089 
00090                 String defaultRobotName = getString(R.string.default_robot);
00091                 String defaultAppName = getString(R.string.default_app);
00092         setDefaultMasterName(defaultRobotName);
00093                 setDefaultAppName(defaultAppName);
00094                 setDashboardResource(R.id.top_bar);
00095                 setMainWindowResource(R.layout.main);
00096 
00097                 super.onCreate(savedInstanceState);
00098 
00099                 cameraView = (RosImageView<sensor_msgs.CompressedImage>) findViewById(R.id.image);
00100                 cameraView.setMessageType(sensor_msgs.CompressedImage._TYPE);
00101                 cameraView.setMessageToBitmapCallable(new BitmapFromCompressedImage());
00102                 virtualJoystickView = (VirtualJoystickView) findViewById(R.id.virtual_joystick);
00103                 refreshButton = (ImageButton) findViewById(R.id.refresh_button);
00104                 saveButton = (ImageButton) findViewById(R.id.save_map);
00105                 backButton = (Button) findViewById(R.id.back_button);
00106 
00107         mapView = (VisualizationView) findViewById(R.id.map_view);
00108         mapView.onCreate(Lists.<Layer>newArrayList());
00109 
00110         refreshButton.setOnClickListener(new View.OnClickListener() {
00111                         @Override
00112                         public void onClick(View view) {
00113                                 // TODO
00114                                 Toast.makeText(MainActivity.this, "refreshing map...",
00115                                                 Toast.LENGTH_SHORT).show();
00116                 mapView.getCamera().jumpToFrame((String) params.get("map_frame", getString(R.string.map_frame)));
00117                         }
00118                 });
00119 
00120                 saveButton.setOnClickListener(new View.OnClickListener() {
00121                         @Override
00122                         public void onClick(View view) {
00123                                 showDialog(NAME_MAP_DIALOG_ID);
00124 
00125                         }
00126 
00127                 });
00128 
00129                 backButton.setOnClickListener(new View.OnClickListener() {
00130                         @Override
00131                         public void onClick(View view) {
00132                                 onBackPressed();
00133                         }
00134                 });
00135 
00136         mapView.getCamera().jumpToFrame((String) params.get("map_frame", getString(R.string.map_frame)));
00137 
00138                 mainLayout = (ViewGroup) findViewById(R.id.main_layout);
00139                 sideLayout = (ViewGroup) findViewById(R.id.side_layout);
00140         }
00141 
00142         @Override
00143         protected Dialog onCreateDialog(int id) {
00144                 Dialog dialog;
00145                 Button button;
00146 
00147                 switch (id) {
00148                 case NAME_MAP_DIALOG_ID:
00149                         dialog = new Dialog(this);
00150                         dialog.setContentView(R.layout.name_map_dialog);
00151                         dialog.setTitle("Save Map");
00152                         final EditText nameField = (EditText) dialog
00153                                         .findViewById(R.id.name_editor);
00154 
00155                         nameField.setOnKeyListener(new View.OnKeyListener() {
00156                                 @Override
00157                                 public boolean onKey(final View view, int keyCode,
00158                                                 KeyEvent event) {
00159                                         if (event.getAction() == KeyEvent.ACTION_DOWN
00160                                                         && keyCode == KeyEvent.KEYCODE_ENTER) {
00161                                                 safeShowWaitingDialog("Saving map...");
00162                                                 try {
00163                             final MapManager mapManager = new MapManager(MainActivity.this, remaps);
00164                                                         String name = nameField.getText().toString();
00165                                                         if (name != null) {
00166                                                                 mapManager.setMapName(name);
00167                                                         }
00168                             mapManager.setNameResolver(getMasterNameSpace());
00169                             mapManager.registerCallback(new MapManager.StatusCallback() {
00170                                 @Override
00171                                 public void timeoutCallback() {
00172                                     safeDismissWaitingDialog();
00173                                     safeShowNotiDialog("Error", "Timeout");
00174                                 }
00175                                 @Override
00176                                 public void onSuccessCallback(SaveMapResponse arg0) {
00177                                     safeDismissWaitingDialog();
00178                                     safeShowNotiDialog("Success", "Map saving success!");
00179                                 }
00180                                 @Override
00181                                 public void onFailureCallback(Exception e) {
00182                                    safeDismissWaitingDialog();
00183                                     safeShowNotiDialog("Error", e.getMessage());
00184                                 }
00185                             });
00186 
00187                                                         nodeMainExecutor.execute(mapManager,
00188                                                                         nodeConfiguration.setNodeName("android/save_map"));
00189 
00190                                                 } catch (Exception e) {
00191                                                         e.printStackTrace();
00192                             safeShowNotiDialog("Error", "Error during saving: " + e.toString());
00193                                                 }
00194 
00195                                                 removeDialog(NAME_MAP_DIALOG_ID);
00196                                                 return true;
00197                                         } else {
00198                                                 return false;
00199                                         }
00200                                 }
00201                         });
00202                         button = (Button) dialog.findViewById(R.id.cancel_button);
00203                         button.setOnClickListener(new View.OnClickListener() {
00204                                 @Override
00205                                 public void onClick(View v) {
00206                                         removeDialog(NAME_MAP_DIALOG_ID);
00207                                 }
00208                         });
00209                         break;
00210                 default:
00211                         dialog = null;
00212                 }
00213                 return dialog;
00214         }
00215 
00216         private void safeDismissWaitingDialog() {
00217                 runOnUiThread(new Runnable() {
00218                         @Override
00219                         public void run() {
00220                                 if (waitingDialog != null) {
00221                                         waitingDialog.dismiss();
00222                                         waitingDialog = null;
00223                                 }
00224                         }
00225                 });
00226         }
00227 
00228         private void safeShowWaitingDialog(final CharSequence message) {
00229                 runOnUiThread(new Runnable() {
00230                         @Override
00231                         public void run() {
00232                                 if (waitingDialog != null) {
00233                                         waitingDialog.dismiss();
00234                                         waitingDialog = null;
00235                                 }
00236                                 waitingDialog = ProgressDialog.show(MainActivity.this, "",
00237                                                 message, true);
00238                         }
00239                 });
00240         }
00241 
00242         private void safeShowNotiDialog(final String title, final CharSequence message) {
00243                 runOnUiThread(new Runnable() {
00244                         @Override
00245                         public void run() {
00246                                 if (notiDialog != null) {
00247                     notiDialog.dismiss();
00248                     notiDialog = null;
00249                                 }
00250                                 if (waitingDialog != null) {
00251                                         waitingDialog.dismiss();
00252                                         waitingDialog = null;
00253                                 }
00254                                 AlertDialog.Builder dialog = new AlertDialog.Builder(
00255                                                 MainActivity.this);
00256                                 dialog.setTitle(title);
00257                                 dialog.setMessage(message);
00258                                 dialog.setNeutralButton("Ok",
00259                                                 new DialogInterface.OnClickListener() {
00260                                                         @Override
00261                                                         public void onClick(DialogInterface dlog, int i) {
00262                                                                 dlog.dismiss();
00263                                                         }
00264                                                 });
00265                 notiDialog = dialog.show();
00266                         }
00267                 });
00268         }
00269 
00270         @Override
00271         protected void init(NodeMainExecutor nodeMainExecutor) {
00272 
00273                 super.init(nodeMainExecutor);
00274                 this.nodeMainExecutor = nodeMainExecutor;
00275 
00276                 nodeConfiguration = NodeConfiguration.newPublic(InetAddressFactory
00277                                 .newNonLoopback().getHostAddress(), getMasterUri());
00278 
00279         String joyTopic = remaps.get(getString(R.string.joystick_topic));
00280         String camTopic = remaps.get(getString(R.string.camera_topic));
00281 
00282         NameResolver appNameSpace = getMasterNameSpace();
00283         joyTopic = appNameSpace.resolve(joyTopic).toString();
00284         camTopic = appNameSpace.resolve(camTopic).toString();
00285         cameraView.setTopicName(camTopic);
00286         virtualJoystickView.setTopicName(joyTopic);
00287 
00288                 nodeMainExecutor.execute(cameraView,
00289                                 nodeConfiguration.setNodeName("android/camera_view"));
00290                 nodeMainExecutor.execute(virtualJoystickView,
00291                                 nodeConfiguration.setNodeName("android/virtual_joystick"));
00292 
00293         ViewControlLayer viewControlLayer = new ViewControlLayer(this,
00294                 nodeMainExecutor.getScheduledExecutorService(), cameraView,
00295                 mapView, mainLayout, sideLayout, params);
00296 
00297         String mapTopic   = remaps.get(getString(R.string.map_topic));
00298         String scanTopic  = remaps.get(getString(R.string.scan_topic));
00299         String robotFrame = (String) params.get("robot_frame", getString(R.string.robot_frame));
00300 
00301         occupancyGridLayer = new OccupancyGridLayer(appNameSpace.resolve(mapTopic).toString());
00302         laserScanLayer = new LaserScanLayer(appNameSpace.resolve(scanTopic).toString());
00303         robotLayer = new RobotLayer(robotFrame);
00304 
00305         mapView.addLayer(viewControlLayer);
00306         mapView.addLayer(occupancyGridLayer);
00307         mapView.addLayer(laserScanLayer);
00308         mapView.addLayer(robotLayer);
00309 
00310         mapView.init(nodeMainExecutor);
00311         viewControlLayer.addListener(new CameraControlListener() {
00312             @Override
00313             public void onZoom(float focusX, float focusY, float factor) {}
00314             @Override
00315             public void onDoubleTap(float x, float y) {}
00316             @Override
00317             public void onTranslate(float distanceX, float distanceY) {}
00318             @Override
00319             public void onRotate(float focusX, float focusY, double deltaAngle) {}
00320         });
00321 
00322         // dwlee
00323         //what is a main purpose of this function?
00324 //        NtpTimeProvider ntpTimeProvider = new NtpTimeProvider(
00325 //                              InetAddressFactory.newFromHostString("192.168.0.1"),
00326 //                              nodeMainExecutor.getScheduledExecutorService());
00327 //              ntpTimeProvider.startPeriodicUpdates(1, TimeUnit.MINUTES);
00328 //              nodeConfiguration.setTimeProvider(ntpTimeProvider);
00329                 nodeMainExecutor.execute(mapView, nodeConfiguration.setNodeName("android/map_view"));
00330         }
00331 
00332         @Override
00333         public boolean onCreateOptionsMenu(Menu menu) {
00334                 menu.add(0, 0, 0, R.string.stop_app);
00335                 return super.onCreateOptionsMenu(menu);
00336         }
00337 
00338         @Override
00339         public boolean onOptionsItemSelected(MenuItem item) {
00340                 super.onOptionsItemSelected(item);
00341                 switch (item.getItemId()) {
00342                 case 0:
00343                         onDestroy();
00344                         break;
00345                 }
00346                 return true;
00347         }
00348 
00349 }


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