Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 package org.ros.android.view.visualization.layer;
00018
00019 import com.google.common.base.Preconditions;
00020
00021 import android.os.Handler;
00022 import org.jboss.netty.buffer.ChannelBuffer;
00023 import org.ros.android.view.visualization.Camera;
00024 import org.ros.android.view.visualization.TextureBitmap;
00025 import org.ros.internal.message.MessageBuffers;
00026 import org.ros.message.MessageListener;
00027 import org.ros.namespace.GraphName;
00028 import org.ros.node.ConnectedNode;
00029 import org.ros.rosjava_geometry.FrameName;
00030 import org.ros.rosjava_geometry.FrameTransformTree;
00031 import org.ros.rosjava_geometry.Transform;
00032
00033 import javax.microedition.khronos.opengles.GL10;
00034
00038 public class OccupancyGridLayer extends SubscriberLayer<nav_msgs.OccupancyGrid> implements TfLayer {
00039
00043 private static final int COLOR_OCCUPIED = 0xdfffffff;
00044
00048 private static final int COLOR_FREE = 0xff8d8d8d;
00049
00053 private static final int COLOR_UNKNOWN = 0xff000000;
00054
00055 private final ChannelBuffer pixels;
00056 private final TextureBitmap textureBitmap;
00057
00058 private boolean ready;
00059 private FrameName frame;
00060 private GL10 previousGl;
00061
00062 public OccupancyGridLayer(String topic) {
00063 this(GraphName.of(topic));
00064 }
00065
00066 public OccupancyGridLayer(GraphName topic) {
00067 super(topic, nav_msgs.OccupancyGrid._TYPE);
00068 pixels = MessageBuffers.dynamicBuffer();
00069 textureBitmap = new TextureBitmap();
00070 ready = false;
00071 }
00072
00073 @Override
00074 public void draw(GL10 gl) {
00075 if (previousGl != gl) {
00076 textureBitmap.clearHandle();
00077 previousGl = gl;
00078 }
00079 if (ready) {
00080 textureBitmap.draw(gl);
00081 }
00082 }
00083
00084 @Override
00085 public FrameName getFrame() {
00086 return frame;
00087 }
00088
00089 @Override
00090 public void onStart(ConnectedNode connectedNode, Handler handler,
00091 FrameTransformTree frameTransformTree, Camera camera) {
00092 super.onStart(connectedNode, handler, frameTransformTree, camera);
00093 previousGl = null;
00094 getSubscriber().addMessageListener(new MessageListener<nav_msgs.OccupancyGrid>() {
00095 @Override
00096 public void onNewMessage(nav_msgs.OccupancyGrid message) {
00097 update(message);
00098 }
00099 });
00100 }
00101
00102 private void update(nav_msgs.OccupancyGrid message) {
00103 int stride = message.getInfo().getWidth();
00104 Preconditions.checkArgument(stride <= 1024);
00105 Preconditions.checkArgument(message.getInfo().getHeight() <= 1024);
00106 ChannelBuffer buffer = message.getData();
00107 while (buffer.readable()) {
00108 byte pixel = buffer.readByte();
00109 if (pixel == -1) {
00110 pixels.writeInt(COLOR_UNKNOWN);
00111 } else if (pixel == 0) {
00112 pixels.writeInt(COLOR_FREE);
00113 } else {
00114 pixels.writeInt(COLOR_OCCUPIED);
00115 }
00116 }
00117 float resolution = message.getInfo().getResolution();
00118 Transform origin = Transform.fromPoseMessage(message.getInfo().getOrigin());
00119 textureBitmap.updateFromPixelBuffer(pixels, stride, resolution, origin, COLOR_UNKNOWN);
00120 pixels.clear();
00121 frame = FrameName.of(message.getHeader().getFrameId());
00122 ready = true;
00123 }
00124 }