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.view.GestureDetector;
00022 import android.view.MotionEvent;
00023 import org.ros.android.view.visualization.VisualizationView;
00024 import org.ros.android.view.visualization.shape.PixelSpacePoseShape;
00025 import org.ros.android.view.visualization.shape.Shape;
00026 import org.ros.namespace.GraphName;
00027 import org.ros.node.ConnectedNode;
00028 import org.ros.node.Node;
00029 import org.ros.node.topic.Publisher;
00030 import org.ros.rosjava_geometry.Transform;
00031 import org.ros.rosjava_geometry.Vector3;
00032
00033 import javax.microedition.khronos.opengles.GL10;
00034
00038 public class PosePublisherLayer extends DefaultLayer {
00039
00040 private Shape shape;
00041 private Publisher<geometry_msgs.PoseStamped> posePublisher;
00042 private boolean visible;
00043 private GraphName topic;
00044 private GestureDetector gestureDetector;
00045 private Transform pose;
00046 private ConnectedNode connectedNode;
00047
00048 public PosePublisherLayer(String topic) {
00049 this(GraphName.of(topic));
00050 }
00051
00052 public PosePublisherLayer(GraphName topic) {
00053 this.topic = topic;
00054 visible = false;
00055 }
00056
00057 @Override
00058 public void draw(VisualizationView view, GL10 gl) {
00059 if (visible) {
00060 Preconditions.checkNotNull(pose);
00061 shape.draw(view, gl);
00062 }
00063 }
00064
00065 private double angle(double x1, double y1, double x2, double y2) {
00066 double deltaX = x1 - x2;
00067 double deltaY = y1 - y2;
00068 return Math.atan2(deltaY, deltaX);
00069 }
00070
00071 @Override
00072 public boolean onTouchEvent(VisualizationView view, MotionEvent event) {
00073 if (visible) {
00074 Preconditions.checkNotNull(pose);
00075 if (event.getAction() == MotionEvent.ACTION_MOVE) {
00076 Vector3 poseVector = pose.apply(Vector3.zero());
00077 Vector3 pointerVector =
00078 view.getCamera().toCameraFrame((int) event.getX(), (int) event.getY());
00079 double angle =
00080 angle(pointerVector.getX(), pointerVector.getY(), poseVector.getX(), poseVector.getY());
00081 pose = Transform.translation(poseVector).multiply(Transform.zRotation(angle));
00082 shape.setTransform(pose);
00083 return true;
00084 }
00085 if (event.getAction() == MotionEvent.ACTION_UP) {
00086 posePublisher.publish(pose.toPoseStampedMessage(view.getCamera().getFrame(),
00087 connectedNode.getCurrentTime(), posePublisher.newMessage()));
00088 visible = false;
00089 return true;
00090 }
00091 }
00092 gestureDetector.onTouchEvent(event);
00093 return false;
00094 }
00095
00096 @Override
00097 public void onStart(final VisualizationView view, ConnectedNode connectedNode) {
00098 this.connectedNode = connectedNode;
00099 shape = new PixelSpacePoseShape();
00100 posePublisher = connectedNode.newPublisher(topic, geometry_msgs.PoseStamped._TYPE);
00101 view.post(new Runnable() {
00102 @Override
00103 public void run() {
00104 gestureDetector =
00105 new GestureDetector(view.getContext(), new GestureDetector.SimpleOnGestureListener() {
00106 @Override
00107 public void onLongPress(MotionEvent e) {
00108 pose =
00109 Transform.translation(view.getCamera().toCameraFrame((int) e.getX(),
00110 (int) e.getY()));
00111 shape.setTransform(pose);
00112 visible = true;
00113 }
00114 });
00115 }
00116 });
00117 }
00118
00119 @Override
00120 public void onShutdown(VisualizationView view, Node node) {
00121 posePublisher.shutdown();
00122 }
00123 }