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 org.ros.android.view.visualization.VisualizationView;
00022 import android.graphics.Bitmap;
00023 import android.graphics.BitmapFactory;
00024 import org.jboss.netty.buffer.ChannelBuffer;
00025 import org.ros.android.view.visualization.TextureBitmap;
00026 import org.ros.message.MessageListener;
00027 import org.ros.namespace.GraphName;
00028 import org.ros.node.ConnectedNode;
00029 import org.ros.rosjava_geometry.Transform;
00030
00031 import javax.microedition.khronos.opengles.GL10;
00032
00037 public class CompressedOccupancyGridLayer extends SubscriberLayer<nav_msgs.OccupancyGrid> implements
00038 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 TextureBitmap textureBitmap;
00056
00057 private boolean ready;
00058 private GraphName frame;
00059
00060 public CompressedOccupancyGridLayer(String topic) {
00061 this(GraphName.of(topic));
00062 }
00063
00064 public CompressedOccupancyGridLayer(GraphName topic) {
00065 super(topic, nav_msgs.OccupancyGrid._TYPE);
00066 textureBitmap = new TextureBitmap();
00067 ready = false;
00068 }
00069
00070 @Override
00071 public void draw(VisualizationView view, GL10 gl) {
00072 if (ready) {
00073 textureBitmap.draw(view, gl);
00074 }
00075 }
00076
00077 @Override
00078 public GraphName getFrame() {
00079 return frame;
00080 }
00081
00082 @Override
00083 public void onStart(VisualizationView view, ConnectedNode connectedNode) {
00084 super.onStart(view, connectedNode);
00085 getSubscriber().addMessageListener(new MessageListener<nav_msgs.OccupancyGrid>() {
00086 @Override
00087 public void onNewMessage(nav_msgs.OccupancyGrid message) {
00088 update(message);
00089 }
00090 });
00091 }
00092
00093 void update(nav_msgs.OccupancyGrid message) {
00094 ChannelBuffer buffer = message.getData();
00095 Bitmap bitmap =
00096 BitmapFactory.decodeByteArray(buffer.array(), buffer.arrayOffset(), buffer.readableBytes());
00097 int stride = bitmap.getWidth();
00098 int height = bitmap.getHeight();
00099 Preconditions.checkArgument(stride <= 1024);
00100 Preconditions.checkArgument(height <= 1024);
00101 int[] pixels = new int[stride * height];
00102 bitmap.getPixels(pixels, 0, stride, 0, 0, stride, height);
00103 for (int i = 0; i < pixels.length; i++) {
00104
00105 if (pixels[i] == 0xffffffff) {
00106 pixels[i] = COLOR_UNKNOWN;
00107 } else if (pixels[i] == 0xff000000) {
00108 pixels[i] = COLOR_FREE;
00109 } else {
00110 pixels[i] = COLOR_OCCUPIED;
00111 }
00112 }
00113 float resolution = message.getInfo().getResolution();
00114 Transform origin = Transform.fromPoseMessage(message.getInfo().getOrigin());
00115 textureBitmap.updateFromPixelArray(pixels, stride, resolution, origin, COLOR_UNKNOWN);
00116 frame = GraphName.of(message.getHeader().getFrameId());
00117 ready = true;
00118 }
00119 }