00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 package com.github.rosjava.android_apps.map_nav;
00018
00019 import android.app.AlertDialog;
00020 import android.app.ProgressDialog;
00021 import android.content.DialogInterface;
00022 import android.os.Bundle;
00023 import android.util.Log;
00024 import android.view.Menu;
00025 import android.view.MenuItem;
00026 import android.view.View;
00027 import android.view.ViewGroup;
00028 import android.widget.Button;
00029
00030 import com.github.rosjava.android_remocons.common_tools.apps.RosAppActivity;
00031 import com.google.common.collect.Lists;
00032
00033 import org.ros.address.InetAddressFactory;
00034 import org.ros.android.BitmapFromCompressedImage;
00035 import org.ros.android.view.RosImageView;
00036 import org.ros.android.view.VirtualJoystickView;
00037 import org.ros.android.view.visualization.VisualizationView;
00038 import org.ros.android.view.visualization.layer.CameraControlListener;
00039 import org.ros.android.view.visualization.layer.LaserScanLayer;
00040 import org.ros.android.view.visualization.layer.Layer;
00041 import org.ros.android.view.visualization.layer.OccupancyGridLayer;
00042 import org.ros.android.view.visualization.layer.PathLayer;
00043 import org.ros.exception.RemoteException;
00044 import org.ros.namespace.NameResolver;
00045 import org.ros.node.NodeConfiguration;
00046 import org.ros.node.NodeMainExecutor;
00047 import org.ros.node.service.ServiceResponseListener;
00048
00049 import java.sql.Date;
00050 import java.text.DateFormat;
00051 import java.util.List;
00052
00053 import world_canvas_msgs.ListMapsResponse;
00054 import world_canvas_msgs.MapListEntry;
00055 import world_canvas_msgs.PublishMapResponse;
00056
00060 public class MainActivity extends RosAppActivity {
00061
00062 private RosImageView<sensor_msgs.CompressedImage> cameraView;
00063 private VirtualJoystickView virtualJoystickView;
00064 private VisualizationView mapView;
00065 private ViewGroup mainLayout;
00066 private ViewGroup sideLayout;
00067 private Button backButton;
00068 private Button chooseMapButton;
00069 private com.github.rosjava.android_apps.map_nav.MapPosePublisherLayer mapPosePublisherLayer;
00070 private ProgressDialog waitingDialog;
00071 private AlertDialog chooseMapDialog;
00072 private NodeMainExecutor nodeMainExecutor;
00073 private NodeConfiguration nodeConfiguration;
00074
00075 public MainActivity() {
00076
00077
00078
00079 super("Map nav", "Map nav");
00080 }
00081
00082 @SuppressWarnings("unchecked")
00083 @Override
00084 public void onCreate(Bundle savedInstanceState) {
00085
00086 String defaultRobotName = getString(R.string.default_robot);
00087 String defaultAppName = getString(R.string.default_app);
00088 setDefaultMasterName(defaultRobotName);
00089 setDefaultAppName(defaultAppName);
00090 setDashboardResource(R.id.top_bar);
00091 setMainWindowResource(R.layout.main);
00092 super.onCreate(savedInstanceState);
00093
00094 cameraView = (RosImageView<sensor_msgs.CompressedImage>) findViewById(R.id.image);
00095 cameraView.setMessageType(sensor_msgs.CompressedImage._TYPE);
00096 cameraView.setMessageToBitmapCallable(new BitmapFromCompressedImage());
00097 virtualJoystickView = (VirtualJoystickView) findViewById(R.id.virtual_joystick);
00098 backButton = (Button) findViewById(R.id.back_button);
00099 chooseMapButton = (Button) findViewById(R.id.choose_map_button);
00100 mapView = (VisualizationView) findViewById(R.id.map_view);
00101 mapView.onCreate(Lists.<Layer>newArrayList());
00102
00103 backButton.setOnClickListener(new View.OnClickListener() {
00104 @Override
00105 public void onClick(View view) {
00106 onBackPressed();
00107 }
00108 });
00109 chooseMapButton.setOnClickListener(new View.OnClickListener() {
00110 @Override
00111 public void onClick(View view) {
00112 onChooseMapButtonPressed();
00113 }
00114 });
00115
00116 mapView.getCamera().jumpToFrame((String) params.get("map_frame", getString(R.string.map_frame)));
00117 mainLayout = (ViewGroup) findViewById(R.id.main_layout);
00118 sideLayout = (ViewGroup) findViewById(R.id.side_layout);
00119
00120 }
00121
00122 @Override
00123 protected void init(NodeMainExecutor nodeMainExecutor) {
00124
00125 super.init(nodeMainExecutor);
00126
00127 this.nodeMainExecutor = nodeMainExecutor;
00128 nodeConfiguration = NodeConfiguration.newPublic(InetAddressFactory
00129 .newNonLoopback().getHostAddress(), getMasterUri());
00130
00131 String joyTopic = remaps.get(getString(R.string.joystick_topic));
00132 String camTopic = remaps.get(getString(R.string.camera_topic));
00133
00134 NameResolver appNameSpace = getMasterNameSpace();
00135 cameraView.setTopicName(appNameSpace.resolve(camTopic).toString());
00136 virtualJoystickView.setTopicName(appNameSpace.resolve(joyTopic).toString());
00137
00138 nodeMainExecutor.execute(cameraView,
00139 nodeConfiguration.setNodeName("android/camera_view"));
00140 nodeMainExecutor.execute(virtualJoystickView,
00141 nodeConfiguration.setNodeName("android/virtual_joystick"));
00142
00143 com.github.rosjava.android_apps.map_nav.ViewControlLayer viewControlLayer =
00144 new com.github.rosjava.android_apps.map_nav.ViewControlLayer(this,
00145 nodeMainExecutor.getScheduledExecutorService(), cameraView,
00146 mapView, mainLayout, sideLayout, params);
00147
00148 String mapTopic = remaps.get(getString(R.string.map_topic));
00149 String scanTopic = remaps.get(getString(R.string.scan_topic));
00150 String planTopic = remaps.get(getString(R.string.global_plan_topic));
00151 String initTopic = remaps.get(getString(R.string.initial_pose_topic));
00152 String robotFrame = (String) params.get("robot_frame", getString(R.string.robot_frame));
00153
00154 OccupancyGridLayer occupancyGridLayer = new OccupancyGridLayer(appNameSpace.resolve(mapTopic).toString());
00155 LaserScanLayer laserScanLayer = new LaserScanLayer(appNameSpace.resolve(scanTopic).toString());
00156 PathLayer pathLayer = new PathLayer(appNameSpace.resolve(planTopic).toString());
00157 mapPosePublisherLayer = new com.github.rosjava.android_apps.map_nav.MapPosePublisherLayer(this, appNameSpace, params, remaps);
00158 com.github.rosjava.android_apps.map_nav.InitialPoseSubscriberLayer initialPoseSubscriberLayer =
00159 new com.github.rosjava.android_apps.map_nav.InitialPoseSubscriberLayer(appNameSpace.resolve(initTopic).toString(), robotFrame);
00160
00161 mapView.addLayer(viewControlLayer);
00162 mapView.addLayer(occupancyGridLayer);
00163 mapView.addLayer(laserScanLayer);
00164 mapView.addLayer(pathLayer);
00165 mapView.addLayer(mapPosePublisherLayer);
00166 mapView.addLayer(initialPoseSubscriberLayer);
00167
00168 mapView.init(nodeMainExecutor);
00169 viewControlLayer.addListener(new CameraControlListener() {
00170 @Override
00171 public void onZoom(float focusX, float focusY, float factor) {}
00172 @Override
00173 public void onDoubleTap(float x, float y) {}
00174 @Override
00175 public void onTranslate(float distanceX, float distanceY) {}
00176 @Override
00177 public void onRotate(float focusX, float focusY, double deltaAngle) {}
00178 });
00179
00180
00181
00182
00183
00184
00185
00186 nodeMainExecutor.execute(mapView, nodeConfiguration.setNodeName("android/map_view"));
00187
00188 readAvailableMapList();
00189 }
00190
00191 private void onChooseMapButtonPressed() {
00192 readAvailableMapList();
00193 }
00194
00195 public void setPoseClicked(View view) {
00196 setPose();
00197 }
00198
00199 public void setGoalClicked(View view) {
00200 setGoal();
00201 }
00202
00203 private void setPose() {
00204 mapPosePublisherLayer.setPoseMode();
00205 }
00206
00207 private void setGoal() {
00208 mapPosePublisherLayer.setGoalMode();
00209 }
00210
00211 private void readAvailableMapList() {
00212 safeShowWaitingDialog("Waiting...", "Waiting for map list");
00213
00214 com.github.rosjava.android_apps.map_nav.MapManager mapManager = new com.github.rosjava.android_apps.map_nav.MapManager(this, remaps);
00215 mapManager.setNameResolver(getMasterNameSpace());
00216 mapManager.setFunction("list");
00217 safeShowWaitingDialog("Waiting...", "Waiting for map list");
00218 mapManager.setListService(new ServiceResponseListener<ListMapsResponse>() {
00219 @Override
00220 public void onSuccess(ListMapsResponse message) {
00221 Log.i("MapNav", "readAvailableMapList() Success");
00222 safeDismissWaitingDialog();
00223 showMapListDialog(message.getMapList());
00224 }
00225
00226 @Override
00227 public void onFailure(RemoteException e) {
00228 Log.i("MapNav", "readAvailableMapList() Failure");
00229 safeDismissWaitingDialog();
00230 }
00231 });
00232
00233 nodeMainExecutor.execute(mapManager,
00234 nodeConfiguration.setNodeName("android/list_maps"));
00235 }
00236
00240 private void showMapListDialog(final List<MapListEntry> list) {
00241
00242 final CharSequence[] availableMapNames = new CharSequence[list.size()];
00243 for (int i = 0; i < list.size(); i++) {
00244 String displayString;
00245 String name = list.get(i).getName();
00246 Date creationDate = new Date(list.get(i).getDate() * 1000);
00247 String dateTime = DateFormat.getDateTimeInstance(DateFormat.MEDIUM,
00248 DateFormat.SHORT).format(creationDate);
00249 if (name != null && !name.equals("")) {
00250 displayString = name + " " + dateTime;
00251 } else {
00252 displayString = dateTime;
00253 }
00254 availableMapNames[i] = displayString;
00255 }
00256
00257 runOnUiThread(new Runnable() {
00258 @Override
00259 public void run() {
00260 AlertDialog.Builder builder = new AlertDialog.Builder(
00261 MainActivity.this);
00262 builder.setTitle("Choose a map");
00263 builder.setItems(availableMapNames,
00264 new DialogInterface.OnClickListener() {
00265 @Override
00266 public void onClick(DialogInterface dialog,
00267 int itemIndex) {
00268 loadMap(list.get(itemIndex));
00269 }
00270 });
00271 chooseMapDialog = builder.create();
00272 chooseMapDialog.show();
00273 }
00274 });
00275 }
00276
00277 private void loadMap(MapListEntry mapListEntry) {
00278
00279 com.github.rosjava.android_apps.map_nav.MapManager mapManager = new com.github.rosjava.android_apps.map_nav.MapManager(this, remaps);
00280 mapManager.setNameResolver(getMasterNameSpace());
00281 mapManager.setFunction("publish");
00282 mapManager.setMapId(mapListEntry.getMapId());
00283
00284 safeShowWaitingDialog("Waiting...", "Loading map");
00285 try {
00286 mapManager
00287 .setPublishService(new ServiceResponseListener<PublishMapResponse>() {
00288 @Override
00289 public void onSuccess(PublishMapResponse message) {
00290 Log.i("MapNav", "loadMap() Success");
00291 safeDismissWaitingDialog();
00292
00293 }
00294
00295 @Override
00296 public void onFailure(RemoteException e) {
00297 Log.i("MapNav", "loadMap() Failure");
00298 safeDismissWaitingDialog();
00299 }
00300 });
00301 } catch (Throwable ex) {
00302 Log.e("MapNav", "loadMap() caught exception.", ex);
00303 safeDismissWaitingDialog();
00304 }
00305 nodeMainExecutor.execute(mapManager,
00306 nodeConfiguration.setNodeName("android/publish_map"));
00307 }
00308
00309 private void safeDismissChooseMapDialog() {
00310 runOnUiThread(new Runnable() {
00311 @Override
00312 public void run() {
00313 if (chooseMapDialog != null) {
00314 chooseMapDialog.dismiss();
00315 chooseMapDialog = null;
00316 }
00317 }
00318 });
00319 }
00320
00321 private void showWaitingDialog(final CharSequence title,
00322 final CharSequence message) {
00323 dismissWaitingDialog();
00324 waitingDialog = ProgressDialog.show(MainActivity.this, title, message,
00325 true);
00326 waitingDialog.setProgressStyle(ProgressDialog.STYLE_SPINNER);
00327 }
00328
00329 private void dismissWaitingDialog() {
00330 if (waitingDialog != null) {
00331 waitingDialog.dismiss();
00332 waitingDialog = null;
00333 }
00334 }
00335
00336 private void safeShowWaitingDialog(final CharSequence title,
00337 final CharSequence message) {
00338 runOnUiThread(new Runnable() {
00339 @Override
00340 public void run() {
00341 showWaitingDialog(title, message);
00342 }
00343 });
00344 }
00345
00346 private void safeDismissWaitingDialog() {
00347 runOnUiThread(new Runnable() {
00348 @Override
00349 public void run() {
00350 dismissWaitingDialog();
00351 }
00352 });
00353 }
00354
00355 @Override
00356 public boolean onCreateOptionsMenu(Menu menu) {
00357 menu.add(0, 0, 0, R.string.stop_app);
00358 return super.onCreateOptionsMenu(menu);
00359 }
00360
00361 @Override
00362 public boolean onOptionsItemSelected(MenuItem item) {
00363 super.onOptionsItemSelected(item);
00364 switch (item.getItemId()) {
00365 case 0:
00366 onDestroy();
00367 break;
00368 }
00369 return true;
00370 }
00371 }