PoseSubscriberLayer.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.visualization.layer;
00018 
00019 import org.ros.android.view.visualization.VisualizationView;
00020 import org.ros.android.view.visualization.shape.GoalShape;
00021 import org.ros.android.view.visualization.shape.Shape;
00022 import org.ros.message.MessageListener;
00023 import org.ros.namespace.GraphName;
00024 import org.ros.node.ConnectedNode;
00025 import org.ros.rosjava_geometry.FrameTransform;
00026 import org.ros.rosjava_geometry.Transform;
00027 
00028 import javax.microedition.khronos.opengles.GL10;
00029 
00033 public class PoseSubscriberLayer extends SubscriberLayer<geometry_msgs.PoseStamped> implements
00034     TfLayer {
00035 
00036   private final GraphName targetFrame;
00037 
00038   private Shape shape;
00039   private boolean ready;
00040 
00041   public PoseSubscriberLayer(String topic) {
00042     this(GraphName.of(topic));
00043   }
00044 
00045   public PoseSubscriberLayer(GraphName topic) {
00046     super(topic, geometry_msgs.PoseStamped._TYPE);
00047     targetFrame = GraphName.of("map");
00048     ready = false;
00049   }
00050 
00051   @Override
00052   public void draw(VisualizationView view, GL10 gl) {
00053     if (ready) {
00054       shape.draw(view, gl);
00055     }
00056   }
00057 
00058   @Override
00059   public void onStart(final VisualizationView view, ConnectedNode connectedNode) {
00060     super.onStart(view, connectedNode);
00061     shape = new GoalShape();
00062     getSubscriber().addMessageListener(new MessageListener<geometry_msgs.PoseStamped>() {
00063       @Override
00064       public void onNewMessage(geometry_msgs.PoseStamped pose) {
00065         GraphName source = GraphName.of(pose.getHeader().getFrameId());
00066         FrameTransform frameTransform = view.getFrameTransformTree().transform(source, targetFrame);
00067         if (frameTransform != null) {
00068           Transform poseTransform = Transform.fromPoseMessage(pose.getPose());
00069           shape.setTransform(frameTransform.getTransform().multiply(poseTransform));
00070           ready = true;
00071         }
00072       }
00073     });
00074   }
00075 
00076   @Override
00077   public GraphName getFrame() {
00078     return targetFrame;
00079   }
00080 }


android_core
Author(s): Damon Kohler
autogenerated on Thu Jun 6 2019 21:20:07