DistanceView.java
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2011 Google Inc.
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 org.ros.android.view;
00018 
00019 import android.content.Context;
00020 import android.graphics.PixelFormat;
00021 import android.opengl.GLSurfaceView;
00022 import android.util.AttributeSet;
00023 import android.view.MotionEvent;
00024 import android.view.View;
00025 import android.view.View.OnTouchListener;
00026 import org.ros.message.MessageListener;
00027 import org.ros.namespace.GraphName;
00028 import org.ros.node.ConnectedNode;
00029 import org.ros.node.Node;
00030 import org.ros.node.NodeMain;
00031 import org.ros.node.topic.Subscriber;
00032 import sensor_msgs.LaserScan;
00033 
00034 import java.util.ArrayList;
00035 import java.util.List;
00036 
00046 public class DistanceView extends GLSurfaceView implements OnTouchListener, NodeMain,
00047     MessageListener<sensor_msgs.LaserScan> {
00048 
00052   private String laserTopic;
00057   private double contactDistance;
00062   private double normalizedZoomValue;
00067   private DistanceRenderer distanceRenderer;
00068 
00074   public DistanceView(Context context) {
00075     this(context, null);
00076   }
00077   
00078   public DistanceView(Context context, AttributeSet attrs) {
00079     super(context, attrs);
00080     distanceRenderer = new DistanceRenderer();
00081     setEGLConfigChooser(8, 8, 8, 8, 16, 0);
00082     getHolder().setFormat(PixelFormat.TRANSLUCENT);
00083     setZOrderOnTop(true);
00084     setRenderer(distanceRenderer);
00085     // This is important since the display needs to be updated only when new
00086     // data is received.
00087     setRenderMode(GLSurfaceView.RENDERMODE_WHEN_DIRTY);
00088   }
00089 
00096   public void setTopicName(String topicName) {
00097     this.laserTopic = topicName;
00098   }
00099 
00100   @Override
00101   public GraphName getDefaultNodeName() {
00102     return GraphName.of("android_honeycomb_mr2/distance_view");
00103   }
00104 
00105   @Override
00106   public void onStart(ConnectedNode connectedNode) {
00107     // Subscribe to the laser scans.
00108     Subscriber<sensor_msgs.LaserScan> laserScanSubscriber =
00109         connectedNode.newSubscriber(laserTopic, sensor_msgs.LaserScan._TYPE);
00110     laserScanSubscriber.addMessageListener(this);
00111     // Subscribe to the command velocity. This is needed for auto adjusting the
00112     // zoom in ZoomMode.VELOCITY_ZOOM_MODE mode.
00113     Subscriber<geometry_msgs.Twist> twistSubscriber =
00114         connectedNode.newSubscriber("cmd_vel", geometry_msgs.Twist._TYPE);
00115     twistSubscriber.addMessageListener(new MessageListener<geometry_msgs.Twist>() {
00116       @Override
00117       public void onNewMessage(final geometry_msgs.Twist robotVelocity) {
00118         post(new Runnable() {
00119           @Override
00120           public void run() {
00121             distanceRenderer.currentSpeed(robotVelocity.getLinear().getX());
00122           }
00123         });
00124       }
00125     });
00126     setOnTouchListener(this);
00127     // Load the last saved setting.
00128     distanceRenderer.loadPreferences(this.getContext());
00129   }
00130   
00131   @Override
00132   public void onShutdown(Node node) {
00133   }
00134 
00135   @Override
00136   public void onShutdownComplete(Node node) {
00137     // Save the existing settings before exiting.
00138     distanceRenderer.savePreferences(this.getContext());
00139   }
00140 
00141   @Override
00142   public void onError(Node node, Throwable throwable) {
00143   }
00144 
00145   @Override
00146   public void onNewMessage(final LaserScan message) {
00147     queueEvent(new Runnable() {
00148       @Override
00149       public void run() {
00150         List<Float> outRanges = new ArrayList<Float>();
00151         float minDistToObject = message.getRangeMax();
00152         // Find the distance to the closest object and also create an List
00153         // for the ranges.
00154         for (float range : message.getRanges()) {
00155           outRanges.add(range);
00156           minDistToObject = (minDistToObject > range) ? range : minDistToObject;
00157         }
00158         // Update the renderer with the latest range values.
00159         distanceRenderer.updateRange(outRanges, message.getRangeMax(), message.getRangeMin(),
00160             message.getAngleMin(), message.getAngleIncrement(), minDistToObject);
00161         // Request to render the surface.
00162         requestRender();
00163       }
00164     });
00165   }
00166 
00173   public void setZoomMode(ZoomMode mode) {
00174     distanceRenderer.setZoomMode(mode);
00175   }
00176 
00180   public void lockZoom() {
00181     distanceRenderer.lockZoom();
00182   }
00183 
00187   public void unlockZoom() {
00188     distanceRenderer.unlockZoom();
00189   }
00190 
00198   public void currentSpeed(double speed) {
00199     distanceRenderer.currentSpeed(speed);
00200   }
00201 
00202   @Override
00203   public boolean onTouch(View v, MotionEvent event) {
00204     final int action = event.getAction();
00205     switch (action & MotionEvent.ACTION_MASK) {
00206       case MotionEvent.ACTION_MOVE: {
00207         // Only zoom when there are exactly 2 contacts on the view.
00208         if (event.getPointerCount() == 2) {
00209           // Get the current distance between the 2 contacts.
00210           double currentContactDistance =
00211               calculateDistance(event.getX(0), event.getY(0), event.getX(1), event.getY(1));
00212           // Calculate the delta between the current contact location and the
00213           // previous contact locations. Then add (a fraction of) that delta to
00214           // the existing normalized value for zoom.
00215           // Using half the width of the view provides an appropriate level of
00216           // sensitivity while zooming.
00217           normalizedZoomValue += (currentContactDistance - contactDistance) / (this.getWidth() / 2);
00218           if (normalizedZoomValue > 1) {
00219             normalizedZoomValue = 1;
00220           } else if (normalizedZoomValue < 0) {
00221             normalizedZoomValue = 0;
00222           }
00223           distanceRenderer.setNormalizedZoom((float) normalizedZoomValue);
00224           // Remember the current distance between coordinates for later.
00225           contactDistance = currentContactDistance;
00226         }
00227         break;
00228       }
00229       // When the second contact touches the screen initialize contactDistance
00230       // for the immediate round of interaction.
00231       case MotionEvent.ACTION_POINTER_1_DOWN: {
00232         contactDistance =
00233             calculateDistance(event.getX(0), event.getY(0), event.getX(1), event.getY(1));
00234         break;
00235       }
00236     }
00237     return true;
00238   }
00239 
00240   private double calculateDistance(float x1, float y1, float x2, float y2) {
00241     return Math.sqrt((x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1));
00242   }
00243 }


android_core
Author(s): Damon Kohler
autogenerated on Thu Aug 27 2015 12:11:33