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

Commit

Permalink
Changes use of FrameName back to GraphName now that FrameTransformTre…
Browse files Browse the repository at this point in the history
…e handles GraphNames in a tf2 compatible way.
  • Loading branch information
damonkohler committed Oct 25, 2013
1 parent 7891749 commit 26e3b5e
Show file tree
Hide file tree
Showing 11 changed files with 43 additions and 47 deletions.
1 change: 1 addition & 0 deletions android_15/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
dependencies {
compile 'com.android.support:support-v4:18.0.+'
compile 'org.ros.rosjava_core:rosjava_geometry:0.1.+'
compile 'org.ros.rosjava_messages:visualization_msgs:1.10.+'
compile project(':android_10')
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@
import com.google.common.base.Preconditions;

import org.ros.math.RosMath;
import org.ros.namespace.GraphName;
import org.ros.rosjava_geometry.FrameTransform;
import org.ros.rosjava_geometry.FrameTransformTree;
import org.ros.rosjava_geometry.FrameName;
import org.ros.rosjava_geometry.Transform;
import org.ros.rosjava_geometry.Vector3;

Expand Down Expand Up @@ -62,7 +62,7 @@ public class XYOrthographicCamera {
* instance, base_link, the view follows the robot and the robot itself is in
* the origin.
*/
private FrameName frame;
private GraphName frame;

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

public boolean applyFrameTransform(GL10 gl, FrameName frame) {
public boolean applyFrameTransform(GL10 gl, GraphName frame) {
Preconditions.checkNotNull(frame);
if (this.frame != null) {
FrameTransform frameTransform = frameTransformTree.transform(frame, this.frame);
Expand Down Expand Up @@ -152,7 +152,7 @@ public Vector3 toMetricCoordinates(int x, int y) {
return transform.invert().apply(new Vector3(centeredX, centeredY, 0));
}

public FrameName getFrame() {
public GraphName getFrame() {
return frame;
}

Expand All @@ -163,7 +163,7 @@ public FrameName getFrame() {
*
* @param frame the new camera frame
*/
public void setFrame(FrameName frame) {
public void setFrame(GraphName frame) {
Preconditions.checkNotNull(frame);
synchronized (mutex) {
if (this.frame != null && this.frame != frame) {
Expand All @@ -179,10 +179,10 @@ public void setFrame(FrameName frame) {
}

/**
* @see #setFrame(FrameName)
* @see #setFrame(GraphName)
*/
public void setFrame(String frame) {
setFrame(FrameName.of(frame));
setFrame(GraphName.of(frame));
}

/**
Expand All @@ -191,7 +191,7 @@ public void setFrame(String frame) {
*
* @param frame the new camera frame
*/
public void jumpToFrame(FrameName frame) {
public void jumpToFrame(GraphName frame) {
synchronized (mutex) {
this.frame = frame;
double zoom = getZoom();
Expand All @@ -201,10 +201,10 @@ public void jumpToFrame(FrameName frame) {
}

/**
* @see #jumpToFrame(FrameName)
* @see #jumpToFrame(GraphName)
*/
public void jumpToFrame(String frame) {
jumpToFrame(FrameName.of(frame));
jumpToFrame(GraphName.of(frame));
}

public void setViewport(Viewport viewport) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,9 @@

import android.content.Context;
import android.opengl.GLSurfaceView;

import org.ros.android.view.visualization.layer.Layer;
import org.ros.android.view.visualization.layer.TfLayer;
import org.ros.rosjava_geometry.FrameName;
import org.ros.namespace.GraphName;

import java.util.List;

Expand Down Expand Up @@ -80,7 +79,7 @@ private void drawLayers(GL10 gl) {
for (Layer layer : getLayers()) {
gl.glPushMatrix();
if (layer instanceof TfLayer) {
FrameName layerFrame = ((TfLayer) layer).getFrame();
GraphName layerFrame = ((TfLayer) layer).getFrame();
if (layerFrame != null && camera.applyFrameTransform(gl, layerFrame)) {
layer.draw(context, gl);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,11 @@
import android.os.Handler;

import org.jboss.netty.buffer.ChannelBuffer;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.android.view.visualization.TextureBitmap;
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.rosjava_geometry.FrameName;
import org.ros.rosjava_geometry.FrameTransformTree;
import org.ros.rosjava_geometry.Transform;

Expand Down Expand Up @@ -60,7 +59,7 @@ public class CompressedOccupancyGridLayer extends SubscriberLayer<nav_msgs.Occup
private final TextureBitmap textureBitmap;

private boolean ready;
private FrameName frame;
private GraphName frame;

public CompressedOccupancyGridLayer(String topic) {
this(GraphName.of(topic));
Expand All @@ -80,7 +79,7 @@ public void draw(Context context, GL10 gl) {
}

@Override
public FrameName getFrame() {
public GraphName getFrame() {
return frame;
}

Expand Down Expand Up @@ -119,7 +118,7 @@ void update(nav_msgs.OccupancyGrid message) {
float resolution = message.getInfo().getResolution();
Transform origin = Transform.fromPoseMessage(message.getInfo().getOrigin());
textureBitmap.updateFromPixelArray(pixels, stride, resolution, origin, COLOR_UNKNOWN);
frame = FrameName.of(message.getHeader().getFrameId());
frame = GraphName.of(message.getHeader().getFrameId());
ready = true;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@
import org.ros.android.view.visualization.XYOrthographicCamera;
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.rosjava_geometry.FrameName;
import org.ros.rosjava_geometry.FrameTransformTree;

import java.util.concurrent.locks.Lock;
Expand All @@ -41,7 +41,7 @@ public class GridCellsLayer extends SubscriberLayer<nav_msgs.GridCells> implemen
private final Color color;
private final Lock lock;

private FrameName frame;
private GraphName frame;
private XYOrthographicCamera camera;
private boolean ready;
private nav_msgs.GridCells message;
Expand Down Expand Up @@ -92,7 +92,7 @@ public void onStart(ConnectedNode connectedNode, Handler handler,
getSubscriber().addMessageListener(new MessageListener<nav_msgs.GridCells>() {
@Override
public void onNewMessage(nav_msgs.GridCells data) {
frame = FrameName.of(data.getHeader().getFrameId());
frame = GraphName.of(data.getHeader().getFrameId());
if (frameTransformTree.lookUp(frame) != null) {
if (lock.tryLock()) {
message = data;
Expand All @@ -105,7 +105,7 @@ public void onNewMessage(nav_msgs.GridCells data) {
}

@Override
public FrameName getFrame() {
public GraphName getFrame() {
return frame;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
import org.ros.namespace.GraphName;
import org.ros.node.ConnectedNode;
import org.ros.node.topic.Subscriber;
import org.ros.rosjava_geometry.FrameName;
import org.ros.rosjava_geometry.FrameTransformTree;

import sensor_msgs.LaserScan;
import android.content.Context;

import java.nio.FloatBuffer;
Expand All @@ -49,7 +49,7 @@ public class LaserScanLayer extends SubscriberLayer<sensor_msgs.LaserScan> imple

private final Object mutex;

private FrameName frame;
private GraphName frame;
private XYOrthographicCamera camera;
private FloatBuffer vertexFrontBuffer;
private FloatBuffer vertexBackBuffer;
Expand Down Expand Up @@ -87,7 +87,7 @@ public void onStart(ConnectedNode connectedNode, android.os.Handler handler,
subscriber.addMessageListener(new MessageListener<LaserScan>() {
@Override
public void onNewMessage(LaserScan laserScan) {
frame = FrameName.of(laserScan.getHeader().getFrameId());
frame = GraphName.of(laserScan.getHeader().getFrameId());
updateVertexBuffer(laserScan, LASER_SCAN_STRIDE);
}
});
Expand Down Expand Up @@ -131,7 +131,7 @@ private void updateVertexBuffer(LaserScan laserScan, int stride) {
}

@Override
public FrameName getFrame() {
public GraphName getFrame() {
return frame;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,12 @@
import android.os.Handler;

import org.jboss.netty.buffer.ChannelBuffer;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.android.view.visualization.TextureBitmap;
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.internal.message.MessageBuffers;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.ConnectedNode;
import org.ros.rosjava_geometry.FrameName;
import org.ros.rosjava_geometry.FrameTransformTree;
import org.ros.rosjava_geometry.Transform;

Expand Down Expand Up @@ -58,7 +57,7 @@ public class OccupancyGridLayer extends SubscriberLayer<nav_msgs.OccupancyGrid>
private final TextureBitmap textureBitmap;

private boolean ready;
private FrameName frame;
private GraphName frame;
private GL10 previousGl;

public OccupancyGridLayer(String topic) {
Expand All @@ -84,7 +83,7 @@ public void draw(Context context, GL10 gl) {
}

@Override
public FrameName getFrame() {
public GraphName getFrame() {
return frame;
}

Expand Down Expand Up @@ -120,7 +119,7 @@ private void update(nav_msgs.OccupancyGrid message) {
Transform origin = Transform.fromPoseMessage(message.getInfo().getOrigin());
textureBitmap.updateFromPixelBuffer(pixels, stride, resolution, origin, COLOR_UNKNOWN);
pixels.clear();
frame = FrameName.of(message.getHeader().getFrameId());
frame = GraphName.of(message.getHeader().getFrameId());
ready = true;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.ConnectedNode;
import org.ros.rosjava_geometry.FrameName;
import org.ros.rosjava_geometry.FrameTransformTree;

import java.nio.ByteBuffer;
Expand All @@ -48,7 +47,7 @@ public class PathLayer extends SubscriberLayer<nav_msgs.Path> implements TfLayer

private FloatBuffer vertexBuffer;
private boolean ready;
private FrameName frame;
private GraphName frame;

public PathLayer(String topic) {
this(GraphName.of(topic));
Expand Down Expand Up @@ -90,7 +89,7 @@ private void updateVertexBuffer(nav_msgs.Path path) {
goalVertexByteBuffer.order(ByteOrder.nativeOrder());
vertexBuffer = goalVertexByteBuffer.asFloatBuffer();
if (path.getPoses().size() > 0) {
frame = FrameName.of(path.getPoses().get(0).getHeader().getFrameId());
frame = GraphName.of(path.getPoses().get(0).getHeader().getFrameId());
// Path poses are densely packed and will make the path look like a solid
// line even if it is drawn as points. Skipping poses provides the visual
// point separation were looking for.
Expand All @@ -110,7 +109,7 @@ private void updateVertexBuffer(nav_msgs.Path path) {
}

@Override
public FrameName getFrame() {
public GraphName getFrame() {
return frame;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
import org.ros.namespace.GraphName;
import org.ros.node.ConnectedNode;
import org.ros.rosjava_geometry.FrameTransform;
import org.ros.rosjava_geometry.FrameName;
import org.ros.rosjava_geometry.FrameTransformTree;
import org.ros.rosjava_geometry.Transform;

Expand All @@ -38,7 +37,7 @@
public class PoseSubscriberLayer extends SubscriberLayer<geometry_msgs.PoseStamped> implements
TfLayer {

private final FrameName targetFrame;
private final GraphName targetFrame;

private Shape shape;
private boolean ready;
Expand All @@ -49,7 +48,7 @@ public PoseSubscriberLayer(String topic) {

public PoseSubscriberLayer(GraphName topic) {
super(topic, "geometry_msgs/PoseStamped");
targetFrame = FrameName.of("map");
targetFrame = GraphName.of("map");
ready = false;
}

Expand All @@ -68,7 +67,7 @@ public void onStart(ConnectedNode connectedNode, Handler handler,
getSubscriber().addMessageListener(new MessageListener<geometry_msgs.PoseStamped>() {
@Override
public void onNewMessage(geometry_msgs.PoseStamped pose) {
FrameName source = FrameName.of(pose.getHeader().getFrameId());
GraphName source = GraphName.of(pose.getHeader().getFrameId());
FrameTransform frameTransform = frameTransformTree.transform(source, targetFrame);
if (frameTransform != null) {
Transform poseTransform = Transform.fromPoseMessage(pose.getPose());
Expand All @@ -80,7 +79,7 @@ public void onNewMessage(geometry_msgs.PoseStamped pose) {
}

@Override
public FrameName getFrame() {
public GraphName getFrame() {
return targetFrame;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@
import org.ros.android.view.visualization.XYOrthographicCamera;
import org.ros.android.view.visualization.shape.RobotShape;
import org.ros.android.view.visualization.shape.Shape;
import org.ros.namespace.GraphName;
import org.ros.node.ConnectedNode;
import org.ros.rosjava_geometry.FrameTransformTree;
import org.ros.rosjava_geometry.FrameName;

import javax.microedition.khronos.opengles.GL10;

Expand All @@ -33,16 +33,16 @@
*/
public class RobotLayer extends DefaultLayer implements TfLayer {

private final FrameName frame;
private final GraphName frame;
private final Shape shape;

public RobotLayer(FrameName frame) {
public RobotLayer(GraphName frame) {
this.frame = frame;
shape = new RobotShape();
}

public RobotLayer(String frame) {
this(FrameName.of(frame));
this(GraphName.of(frame));
}

@Override
Expand All @@ -56,7 +56,7 @@ public void onStart(ConnectedNode connectedNode, Handler handler,
}

@Override
public FrameName getFrame() {
public GraphName getFrame() {
return frame;
}
}
Loading

0 comments on commit 26e3b5e

Please sign in to comment.