Skip to content
This repository has been archived by the owner on Nov 9, 2022. It is now read-only.

Commit

Permalink
Renames Camera to XYOrthographicCamera.
Browse files Browse the repository at this point in the history
Fixes camera control gestures that stopped working after Honeycomb.
  • Loading branch information
damonkohler committed Oct 23, 2013
1 parent b463b43 commit 48b4a81
Show file tree
Hide file tree
Showing 16 changed files with 89 additions and 87 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import android.opengl.GLSurfaceView;
import android.util.AttributeSet;
import android.view.MotionEvent;

import org.ros.android.view.visualization.layer.Layer;
import org.ros.exception.RosRuntimeException;
import org.ros.message.MessageListener;
Expand All @@ -45,8 +46,10 @@ public class VisualizationView extends GLSurfaceView implements NodeMain {
private static final boolean DEBUG = false;

private final FrameTransformTree frameTransformTree = new FrameTransformTree();
private final Camera camera = new Camera(frameTransformTree);
private final XYOrthographicRenderer renderer = new XYOrthographicRenderer(camera);
private final XYOrthographicCamera camera = new XYOrthographicCamera(
frameTransformTree);
private final XYOrthographicRenderer renderer = new XYOrthographicRenderer(
camera);
private final List<Layer> layers = Lists.newArrayList();
private final CountDownLatch attachedToWindow = new CountDownLatch(1);

Expand Down Expand Up @@ -84,14 +87,14 @@ public boolean onTouchEvent(MotionEvent event) {
return true;
}
}
return false;
return super.onTouchEvent(event);
}

public XYOrthographicRenderer getRenderer() {
return renderer;
}

public Camera getCamera() {
public XYOrthographicCamera getCamera() {
return camera;
}

Expand Down Expand Up @@ -136,7 +139,8 @@ protected void onAttachedToWindow() {
}

private void startTransformListener() {
Subscriber<tf2_msgs.TFMessage> tfSubscriber = connectedNode.newSubscriber("tf", tf2_msgs.TFMessage._TYPE); // tf.tfMessage
Subscriber<tf2_msgs.TFMessage> tfSubscriber = connectedNode.newSubscriber(
"tf", tf2_msgs.TFMessage._TYPE);
tfSubscriber.addMessageListener(new MessageListener<tf2_msgs.TFMessage>() {
@Override
public void onNewMessage(tf2_msgs.TFMessage message) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
* @author damonkohler@google.com (Damon Kohler)
* @author moesenle@google.com (Lorenz Moesenlechner)
*/
public class Camera {
public class XYOrthographicCamera {

/**
* Pixels per meter in the world. If zoom is set to the number of pixels per
Expand Down Expand Up @@ -64,7 +64,7 @@ public class Camera {
*/
private FrameName frame;

public Camera(FrameTransformTree frameTransformTree) {
public XYOrthographicCamera(FrameTransformTree frameTransformTree) {
this.frameTransformTree = frameTransformTree;
mutex = new Object();
resetTransform();
Expand All @@ -81,7 +81,7 @@ public void apply(GL10 gl) {
}
}

public boolean applyFrameTransform(GL10 gl, FrameName frame) {
public boolean applyFrameTransform(GL10 gl, FrameName frame) {
Preconditions.checkNotNull(frame);
if (this.frame != null) {
FrameTransform frameTransform = frameTransformTree.transform(frame, this.frame);
Expand All @@ -95,11 +95,9 @@ public boolean applyFrameTransform(GL10 gl, FrameName frame) {

/**
* Translates the camera.
*
* @param deltaX
* distance to move in x in pixels
* @param deltaY
* distance to move in y in pixels
*
* @param deltaX distance to move in x in pixels
* @param deltaY distance to move in y in pixels
*/
public void translate(double deltaX, double deltaY) {
synchronized (mutex) {
Expand All @@ -109,32 +107,25 @@ public void translate(double deltaX, double deltaY) {

/**
* Rotates the camera round the specified coordinates.
*
* @param focusX
* the x coordinate to focus on
* @param focusY
* the y coordinate to focus on
* @param deltaAngle
* the camera will be rotated by {@code deltaAngle} radians
*
* @param focusX the x coordinate to focus on
* @param focusY the y coordinate to focus on
* @param deltaAngle the camera will be rotated by {@code deltaAngle} radians
*/
public void rotate(double focusX, double focusY, double deltaAngle) {
synchronized (mutex) {
Transform focus = Transform.translation(toMetricCoordinates((int) focusX, (int) focusY));
transform =
transform.multiply(focus).multiply(Transform.zRotation(deltaAngle))
.multiply(focus.invert());
transform = transform.multiply(focus).multiply(Transform.zRotation(deltaAngle))
.multiply(focus.invert());
}
}

/**
* Zooms the camera around the specified focus coordinates.
*
* @param focusX
* the x coordinate to focus on
* @param focusY
* the y coordinate to focus on
* @param factor
* the zoom will be scaled by this factor
*
* @param focusX the x coordinate to focus on
* @param focusY the y coordinate to focus on
* @param factor the zoom will be scaled by this factor
*/
public void zoom(double focusX, double focusY, double factor) {
synchronized (mutex) {
Expand All @@ -153,7 +144,7 @@ public double getZoom() {

/**
* @return the metric coordinates of the provided pixel coordinates where the
* origin is the top left corner of the view
* origin is the top left corner of the view
*/
public Vector3 toMetricCoordinates(int x, int y) {
double centeredX = x - viewport.getWidth() / 2.0d;
Expand All @@ -167,11 +158,10 @@ public FrameName getFrame() {

/**
* Changes the camera frame to the specified frame.
* <p>
* <p/>
* If possible, the camera will avoid jumping on the next frame.
*
* @param frame
* the new camera frame
*
* @param frame the new camera frame
*/
public void setFrame(FrameName frame) {
Preconditions.checkNotNull(frame);
Expand All @@ -198,9 +188,8 @@ public void setFrame(String frame) {
/**
* Changes the camera frame to the specified frame and aligns the camera with
* the new frame.
*
* @param frame
* the new camera frame
*
* @param frame the new camera frame
*/
public void jumpToFrame(FrameName frame) {
synchronized (mutex) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@ public class XYOrthographicRenderer implements GLSurfaceView.Renderer {
*/
private List<Layer> layers;

private Camera camera;
private XYOrthographicCamera camera;

public XYOrthographicRenderer(Camera camera) {
public XYOrthographicRenderer(XYOrthographicCamera camera) {
this.camera = camera;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,14 @@

import android.content.Context;
import android.os.Handler;
import android.support.v4.view.GestureDetectorCompat;
import android.view.GestureDetector;
import android.view.MotionEvent;
import android.view.ScaleGestureDetector;
import org.ros.android.view.visualization.Camera;

import org.ros.android.view.visualization.RotateGestureDetector;
import org.ros.android.view.visualization.VisualizationView;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.concurrent.ListenerGroup;
import org.ros.concurrent.SignalRunnable;
import org.ros.node.ConnectedNode;
Expand All @@ -33,7 +35,7 @@

/**
* Provides gesture control of the camera for translate, rotate, and zoom.
*
*
* @author damonkohler@google.com (Damon Kohler)
* @author moesenle@google.com (Lorenz Moesenlechner)
*/
Expand All @@ -42,18 +44,17 @@ public class CameraControlLayer extends DefaultLayer {
private final Context context;
private final ListenerGroup<CameraControlListener> listeners;

private GestureDetector translateGestureDetector;
private GestureDetectorCompat translateGestureDetector;
private RotateGestureDetector rotateGestureDetector;
private ScaleGestureDetector zoomGestureDetector;

/**
* Creates a new {@link CameraControlLayer}.
* <p>
* <p/>
* The camera's frame will be set to {@code frame} once when this layer is
* started and always when the camera is translated.
*
* @param context
* the application's {@link Context}
*
* @param context the application's {@link Context}
* @param executorService
*/
public CameraControlLayer(Context context, ExecutorService executorService) {
Expand All @@ -71,21 +72,30 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
|| zoomGestureDetector == null) {
return false;
}
return translateGestureDetector.onTouchEvent(event)
|| rotateGestureDetector.onTouchEvent(event) || zoomGestureDetector.onTouchEvent(event);
final boolean translateGestureHandled = translateGestureDetector.onTouchEvent(event);
final boolean rotateGestureHandled = rotateGestureDetector.onTouchEvent(event);
final boolean zoomGestureHandled = zoomGestureDetector.onTouchEvent(event);
return translateGestureHandled || rotateGestureHandled || zoomGestureHandled ||
super.onTouchEvent(view, event);
}

@Override
public void onStart(ConnectedNode connectedNode, Handler handler,
FrameTransformTree frameTransformTree, final Camera camera) {
FrameTransformTree frameTransformTree, final XYOrthographicCamera camera) {
handler.post(new Runnable() {
@Override
public void run() {
translateGestureDetector =
new GestureDetector(context, new GestureDetector.SimpleOnGestureListener() {
new GestureDetectorCompat(context, new GestureDetector.SimpleOnGestureListener() {
@Override
public boolean onDown(MotionEvent e) {
// This must return true in order for onScroll() to trigger.
return true;
}

@Override
public boolean onScroll(MotionEvent event1, MotionEvent event2,
final float distanceX, final float distanceY) {
final float distanceX, final float distanceY) {
camera.translate(-distanceX, distanceY);
listeners.signal(new SignalRunnable<CameraControlListener>() {
@Override
Expand All @@ -100,7 +110,7 @@ public void run(CameraControlListener listener) {
new RotateGestureDetector(new RotateGestureDetector.OnRotateGestureListener() {
@Override
public boolean onRotate(MotionEvent event1, MotionEvent event2,
final double deltaAngle) {
final double deltaAngle) {
final double focusX = (event1.getX(0) + event1.getX(1)) / 2;
final double focusY = (event1.getY(0) + event1.getY(1)) / 2;
camera.rotate(focusX, focusY, deltaAngle);
Expand All @@ -110,9 +120,7 @@ public void run(CameraControlListener listener) {
listener.onRotate(focusX, focusY, deltaAngle);
}
});
// Don't consume this event in order to allow the zoom gesture
// to also be detected.
return false;
return true;
}
});
zoomGestureDetector =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
import android.graphics.BitmapFactory;
import android.os.Handler;
import org.jboss.netty.buffer.ChannelBuffer;
import org.ros.android.view.visualization.Camera;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.android.view.visualization.TextureBitmap;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
Expand Down Expand Up @@ -84,7 +84,7 @@ public FrameName getFrame() {

@Override
public void onStart(ConnectedNode connectedNode, Handler handler,
FrameTransformTree frameTransformTree, Camera camera) {
FrameTransformTree frameTransformTree, XYOrthographicCamera camera) {
super.onStart(connectedNode, handler, frameTransformTree, camera);
getSubscriber().addMessageListener(new MessageListener<nav_msgs.OccupancyGrid>() {
@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

import android.os.Handler;
import android.view.MotionEvent;
import org.ros.android.view.visualization.Camera;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.android.view.visualization.VisualizationView;
import org.ros.node.ConnectedNode;
import org.ros.node.Node;
Expand All @@ -44,7 +44,7 @@ public boolean onTouchEvent(VisualizationView view, MotionEvent event) {

@Override
public void onStart(ConnectedNode connectedNode, Handler handler,
FrameTransformTree frameTransformTree, Camera camera) {
FrameTransformTree frameTransformTree, XYOrthographicCamera camera) {
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
package org.ros.android.view.visualization.layer;

import android.os.Handler;
import org.ros.android.view.visualization.Camera;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.android.view.visualization.Color;
import org.ros.android.view.visualization.Vertices;
import org.ros.message.MessageListener;
Expand All @@ -40,7 +40,7 @@ public class GridCellsLayer extends SubscriberLayer<nav_msgs.GridCells> implemen
private final Lock lock;

private FrameName frame;
private Camera camera;
private XYOrthographicCamera camera;
private boolean ready;
private nav_msgs.GridCells message;

Expand Down Expand Up @@ -84,7 +84,7 @@ public void draw(GL10 gl) {

@Override
public void onStart(ConnectedNode connectedNode, Handler handler,
final FrameTransformTree frameTransformTree, Camera camera) {
final FrameTransformTree frameTransformTree, XYOrthographicCamera camera) {
super.onStart(connectedNode, handler, frameTransformTree, camera);
this.camera = camera;
getSubscriber().addMessageListener(new MessageListener<nav_msgs.GridCells>() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,21 +16,22 @@

package org.ros.android.view.visualization.layer;

import org.ros.android.view.visualization.Camera;
import org.ros.android.view.visualization.Color;
import org.ros.android.view.visualization.Vertices;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.ConnectedNode;
import org.ros.node.topic.Subscriber;
import org.ros.rosjava_geometry.FrameTransformTree;
import org.ros.rosjava_geometry.FrameName;
import sensor_msgs.LaserScan;
import org.ros.rosjava_geometry.FrameTransformTree;

import java.nio.FloatBuffer;

import javax.microedition.khronos.opengles.GL10;

import sensor_msgs.LaserScan;

/**
* A {@link SubscriberLayer} that visualizes sensor_msgs/LaserScan messages.
*
Expand All @@ -47,7 +48,7 @@ public class LaserScanLayer extends SubscriberLayer<sensor_msgs.LaserScan> imple
private final Object mutex;

private FrameName frame;
private Camera camera;
private XYOrthographicCamera camera;
private FloatBuffer vertexFrontBuffer;
private FloatBuffer vertexBackBuffer;

Expand Down Expand Up @@ -77,7 +78,7 @@ public void draw(GL10 gl) {

@Override
public void onStart(ConnectedNode connectedNode, android.os.Handler handler,
FrameTransformTree frameTransformTree, Camera camera) {
FrameTransformTree frameTransformTree, XYOrthographicCamera camera) {
super.onStart(connectedNode, handler, frameTransformTree, camera);
this.camera = camera;
Subscriber<LaserScan> subscriber = getSubscriber();
Expand Down
Loading

0 comments on commit 48b4a81

Please sign in to comment.