PanTiltView.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;
00018 
00019 import android.content.Context;
00020 import android.content.SharedPreferences;
00021 import android.util.AttributeSet;
00022 import android.view.LayoutInflater;
00023 import android.view.MotionEvent;
00024 import android.view.View;
00025 import android.view.View.OnTouchListener;
00026 import android.widget.ImageView;
00027 import android.widget.RelativeLayout;
00028 import org.ros.android.android_15.R;
00029 import org.ros.namespace.GraphName;
00030 import org.ros.node.ConnectedNode;
00031 import org.ros.node.Node;
00032 import org.ros.node.NodeMain;
00033 import org.ros.node.topic.Publisher;
00034 
00041 public class PanTiltView extends RelativeLayout implements OnTouchListener, NodeMain {
00042 
00043   private static final int INVALID_POINTER_ID = -1;
00044   private static final int INVALID_POINTER_LOCATION = -1;
00054   private static final int MIDDLE_AREA = 0;
00061   private static final int TOP_AREA = 1;
00068   private static final int RIGHT_AREA = 2;
00073   private static final int MIN_TACK_COORDINATE = 35;
00078   private static final int MAX_TACK_COORDINATE = 184;
00083   private static final float GUIDE_LENGTH = (MAX_TACK_COORDINATE - MIN_TACK_COORDINATE);
00084   private static final String SHARED_PREFERENCE_NAME = "PAN_TILT_VIEW_PREFERENCE";
00085   private static final String MIN_PAN_KEY_NAME = "MIN_PAN";
00086   private static final String MAX_PAN_KEY_NAME = "MAX_PAN";
00087   private static final String MIN_TILT_KEY_NAME = "MIN_TILT";
00088   private static final String MAX_TILT_KEY_NAME = "MAX_TILT";
00089   private static final String HOME_PAN_KEY_NAME = "HOME_PAN";
00090   private static final String HOME_TILT_KEY_NAME = "HOME_TILT";
00091 
00092   private Publisher<sensor_msgs.JointState> publisher;
00093 
00097   private RelativeLayout mainLayout;
00098   private ImageView[] topLargeTack;
00099   private ImageView[] topSmallTack;
00100   private ImageView[] rightLargeTack;
00101   private ImageView[] rightSmallTack;
00102   private ImageView[] zoomLitBar;
00103   private ImageView desiredTack;
00104   private ImageView homeIcon;
00110   private int initialPointerLocation;
00115   private float minPan = -1.0f;
00120   private float maxPan = 1.0f;
00125   private float minTilt = -1.0f;
00130   private float maxTilt = 1.0f;
00134   private float homePan = 0f;
00138   private float homeTilt = 0f;
00143   private int pointerId = INVALID_POINTER_ID;
00144 
00145   private int zoomValue = 0;
00146 
00147   public PanTiltView(Context context) {
00148     this(context, null, 0);
00149   }
00150 
00151   public PanTiltView(Context context, AttributeSet attrs) {
00152     this(context, attrs, 0);
00153   }
00154 
00155   public PanTiltView(Context context, AttributeSet attrs, int defStyle) {
00156     super(context, attrs, defStyle);
00157     // Instantiate the elements from the layout XML file.
00158     LayoutInflater.from(context).inflate(R.layout.pan_tilt, this, true);
00159     // Load settings (minPan, maxPan, etc) from the shared preferences.
00160     loadSettings();
00161     initPanTiltWidget();
00162   }
00163 
00164   @Override
00165   public boolean onTouch(View v, MotionEvent event) {
00166     final int action = event.getAction();
00167 
00168     switch (action & MotionEvent.ACTION_MASK) {
00169     case MotionEvent.ACTION_MOVE: {
00170       // Only proceed if the pointer that initiated the interaction is still
00171       // in contact with the screen.
00172       if (pointerId == INVALID_POINTER_ID) {
00173         break;
00174       }
00175       onContactMove(event.getX(event.findPointerIndex(pointerId)),
00176           event.getY(event.findPointerIndex(pointerId)));
00177       break;
00178     }
00179     case MotionEvent.ACTION_DOWN: {
00180       // Get the coordinates of the pointer that is initiating the
00181       // interaction.
00182       pointerId = event.getPointerId(event.getActionIndex());
00183       onContactDown(event.getX(event.getActionIndex()), event.getY(event.getActionIndex()));
00184       break;
00185     }
00186     case MotionEvent.ACTION_POINTER_UP:
00187     case MotionEvent.ACTION_UP: {
00188       // When any pointer (primary or otherwise) fires an UP, prevent further
00189       // the interaction.
00190       pointerId = INVALID_POINTER_ID;
00191       initialPointerLocation = INVALID_POINTER_LOCATION;
00192       break;
00193     }
00194     }
00195     return true;
00196   }
00197 
00207   private void onContactMove(float x, float y) {
00208     // Since movement of the images is done relative to the bottom left of
00209     // the parent, the y value needs to be updated to reflect the coordinates
00210     // relative to the bottom of the parent.
00211     // y = mainLayout.getHeight() - y;
00212     if (initialPointerLocation == MIDDLE_AREA) {
00213       updateTopTack(x);
00214       updateRightTack(y);
00215     } else if (initialPointerLocation == TOP_AREA) {
00216       updateTopTack(x);
00217     } else if (initialPointerLocation == RIGHT_AREA) {
00218       updateRightTack(y);
00219     } else if (x < 75 && y > 120 && y < 248) {
00220       float tmp = (248 - 120) / 6;
00221       if (y < 120 + tmp) {
00222         zoomValue = 5;
00223       } else if (y < 120 + tmp * 2) {
00224         zoomValue = 4;
00225       } else if (y < 120 + tmp * 3) {
00226         zoomValue = 3;
00227       } else if (y < 120 + tmp * 4) {
00228         zoomValue = 2;
00229       } else if (y < 120 + tmp * 5) {
00230         zoomValue = 1;
00231       } else if (y < 120 + tmp * 6) {
00232         zoomValue = 0;
00233       }
00234       updateZoomBars();
00235     }
00236 
00237   }
00238 
00248   private void onContactDown(float x, float y) {
00249     if (x > 75 && x < 357 && y > 50 && y < 278) {
00250       initialPointerLocation = MIDDLE_AREA;
00251       updateTopTack(x);
00252       updateRightTack(y);
00253     } else if (y < 40 && x > 75 && x < 357) {
00254       initialPointerLocation = TOP_AREA;
00255       updateTopTack(x);
00256     } else if (x > 361 && y > 45 && y < 366) {
00257       initialPointerLocation = RIGHT_AREA;
00258       updateRightTack(y);
00259     } else if (x < 75 && y > 55 && y < 120) {
00260       // Quick hack
00261       zoomValue += 1;
00262       if (zoomValue > 5) {
00263         zoomValue = 5;
00264       }
00265       updateZoomBars();
00266     } else if (x < 75 && y > 248) {
00267       // Quick hack
00268       zoomValue -= 1;
00269       if (zoomValue < 0) {
00270         zoomValue = 0;
00271       }
00272       updateZoomBars();
00273     } else if (x < 75 && y > 120 && y < 248) {
00274       float tmp = (248 - 120) / 6;
00275       if (y < 120 + tmp) {
00276         zoomValue = 5;
00277       } else if (y < 120 + tmp * 2) {
00278         zoomValue = 4;
00279       } else if (y < 120 + tmp * 3) {
00280         zoomValue = 3;
00281       } else if (y < 120 + tmp * 4) {
00282         zoomValue = 2;
00283       } else if (y < 120 + tmp * 5) {
00284         zoomValue = 1;
00285       } else if (y < 120 + tmp * 6) {
00286         zoomValue = 0;
00287       }
00288       updateZoomBars();
00289     }
00290 
00291   }
00292 
00293   private void updateZoomBars() {
00294     // Quick hack
00295     for (int i = 0; i < zoomLitBar.length; i++) {
00296       zoomLitBar[4 - i].setVisibility(INVISIBLE);
00297     }
00298     for (int i = 0; i < zoomValue; i++) {
00299       zoomLitBar[4 - i].setVisibility(VISIBLE);
00300     }
00301   }
00302 
00311   private void updateRightTack(float y) {
00312     float offset = desiredTack.getHeight() / 2;
00313     if (y < 40.0f + offset) {
00314       y = 40.0f + offset;
00315     } else if (y > 278.0f - offset) {
00316       y = 278.0f - offset;
00317     } else if (y < (homeIcon.getTranslationY() + homeIcon.getHeight() / 5 + getHeight() / 2)
00318         && y > (homeIcon.getTranslationY() + getHeight() / 2 - homeIcon.getHeight() / 5)) {
00319       y = homeIcon.getTranslationY() + getHeight() / 2;
00320     }
00321     desiredTack.setTranslationY(y - mainLayout.getHeight() / 2);
00322     publishTilt(y);
00323 
00324     float rangeLarge = 12.0f;
00325     float rangeSmall = 50.0f;
00326     for (int i = 0; i < rightLargeTack.length; i++) {
00327       if (Math.abs(y - mainLayout.getHeight() / 2 - rightLargeTack[i].getTranslationY()) < rangeLarge) {
00328         rightLargeTack[i].setAlpha(1.0f);
00329       } else {
00330         rightLargeTack[i].setAlpha(0.0f);
00331       }
00332     }
00333 
00334     for (int i = 0; i < rightSmallTack.length; i++) {
00335       if (Math.abs(y - mainLayout.getHeight() / 2 - rightSmallTack[i].getTranslationY()) < rangeSmall) {
00336         rightSmallTack[i].setAlpha(1.0f
00337             - Math.abs(y - mainLayout.getHeight() / 2 - rightSmallTack[i].getTranslationY())
00338             / rangeSmall);
00339       } else {
00340         rightSmallTack[i].setAlpha(0.0f);
00341       }
00342     }
00343 
00344   }
00345 
00353   private void updateTopTack(float x) {
00354     float offset = desiredTack.getWidth() / 2;
00355     if (x < 75 + offset) {
00356       x = 75 + offset;
00357     } else if (x > 357 - offset) {
00358       x = 357 - offset;
00359     } else if (x < (homeIcon.getTranslationX() + homeIcon.getWidth() / 5 + getWidth() / 2)
00360         && x > (homeIcon.getTranslationX() + getWidth() / 2 - homeIcon.getWidth() / 5)) {
00361       x = homeIcon.getTranslationX() + getWidth() / 2;
00362     }
00363     desiredTack.setTranslationX(x - mainLayout.getWidth() / 2);
00364     publishPan(x);
00365 
00366     float rangeLarge = 13.0f;
00367     float rangeSmall = 50.0f;
00368     for (int i = 0; i < topLargeTack.length; i++) {
00369       if (Math.abs(x - mainLayout.getWidth() / 2 - topLargeTack[i].getTranslationX()) < rangeLarge) {
00370         topLargeTack[i].setAlpha(1.0f);
00371         // topLargeTack[i].setAlpha(1.0f
00372         // - Math.abs(x - mainLayout.getWidth() / 2 -
00373         // topLargeTack[i].getTranslationX())
00374         // / rangeLarge);
00375       } else {
00376         topLargeTack[i].setAlpha(0.0f);
00377       }
00378     }
00379 
00380     for (int i = 0; i < topSmallTack.length; i++) {
00381       if (Math.abs(x - mainLayout.getWidth() / 2 - topSmallTack[i].getTranslationX()) < rangeSmall) {
00382         topSmallTack[i].setAlpha(1.0f
00383             - Math.abs(x - mainLayout.getWidth() / 2 - topSmallTack[i].getTranslationX())
00384             / rangeSmall);
00385       } else {
00386         topSmallTack[i].setAlpha(0.0f);
00387       }
00388     }
00389 
00390   }
00391 
00392   private void initPanTiltWidget() {
00393     mainLayout = (RelativeLayout) findViewById(R.id.pan_tilt_layout);
00394     desiredTack = (ImageView) findViewById(R.id.pt_divet);
00395     topLargeTack = new ImageView[10];
00396     topSmallTack = new ImageView[10];
00397     rightLargeTack = new ImageView[7];
00398     rightSmallTack = new ImageView[7];
00399     for (int i = 0; i < topLargeTack.length; i++) {
00400       topLargeTack[i] = new ImageView(getContext());
00401       topSmallTack[i] = new ImageView(getContext());
00402     }
00403     topLargeTack[0] = (ImageView) findViewById(R.id.pan_large_marker_0);
00404     topLargeTack[1] = (ImageView) findViewById(R.id.pan_large_marker_1);
00405     topLargeTack[2] = (ImageView) findViewById(R.id.pan_large_marker_2);
00406     topLargeTack[3] = (ImageView) findViewById(R.id.pan_large_marker_3);
00407     topLargeTack[4] = (ImageView) findViewById(R.id.pan_large_marker_4);
00408     topLargeTack[5] = (ImageView) findViewById(R.id.pan_large_marker_5);
00409     topLargeTack[6] = (ImageView) findViewById(R.id.pan_large_marker_6);
00410     topLargeTack[7] = (ImageView) findViewById(R.id.pan_large_marker_7);
00411     topLargeTack[8] = (ImageView) findViewById(R.id.pan_large_marker_8);
00412     topLargeTack[9] = (ImageView) findViewById(R.id.pan_large_marker_9);
00413     topSmallTack[0] = (ImageView) findViewById(R.id.pan_small_marker_0);
00414     topSmallTack[1] = (ImageView) findViewById(R.id.pan_small_marker_1);
00415     topSmallTack[2] = (ImageView) findViewById(R.id.pan_small_marker_2);
00416     topSmallTack[3] = (ImageView) findViewById(R.id.pan_small_marker_3);
00417     topSmallTack[4] = (ImageView) findViewById(R.id.pan_small_marker_4);
00418     topSmallTack[5] = (ImageView) findViewById(R.id.pan_small_marker_5);
00419     topSmallTack[6] = (ImageView) findViewById(R.id.pan_small_marker_6);
00420     topSmallTack[7] = (ImageView) findViewById(R.id.pan_small_marker_7);
00421     topSmallTack[8] = (ImageView) findViewById(R.id.pan_small_marker_8);
00422     topSmallTack[9] = (ImageView) findViewById(R.id.pan_small_marker_9);
00423     for (int i = 0; i < topLargeTack.length; i++) {
00424       topLargeTack[i].setAlpha(0.0f);
00425       topSmallTack[i].setAlpha(0.0f);
00426     }
00427     for (int i = 0; i < rightLargeTack.length; i++) {
00428       rightLargeTack[i] = new ImageView(getContext());
00429       rightSmallTack[i] = new ImageView(getContext());
00430     }
00431     rightLargeTack[0] = (ImageView) findViewById(R.id.tilt_large_marker_0);
00432     rightLargeTack[1] = (ImageView) findViewById(R.id.tilt_large_marker_1);
00433     rightLargeTack[2] = (ImageView) findViewById(R.id.tilt_large_marker_2);
00434     rightLargeTack[3] = (ImageView) findViewById(R.id.tilt_large_marker_3);
00435     rightLargeTack[4] = (ImageView) findViewById(R.id.tilt_large_marker_4);
00436     rightLargeTack[5] = (ImageView) findViewById(R.id.tilt_large_marker_5);
00437     rightLargeTack[6] = (ImageView) findViewById(R.id.tilt_large_marker_6);
00438     rightSmallTack[0] = (ImageView) findViewById(R.id.tilt_small_marker_0);
00439     rightSmallTack[1] = (ImageView) findViewById(R.id.tilt_small_marker_1);
00440     rightSmallTack[2] = (ImageView) findViewById(R.id.tilt_small_marker_2);
00441     rightSmallTack[3] = (ImageView) findViewById(R.id.tilt_small_marker_3);
00442     rightSmallTack[4] = (ImageView) findViewById(R.id.tilt_small_marker_4);
00443     rightSmallTack[5] = (ImageView) findViewById(R.id.tilt_small_marker_5);
00444     rightSmallTack[6] = (ImageView) findViewById(R.id.tilt_small_marker_6);
00445     for (int i = 0; i < rightLargeTack.length; i++) {
00446       rightLargeTack[i].setAlpha(0.0f);
00447       rightSmallTack[i].setAlpha(0.0f);
00448     }
00449 
00450     zoomLitBar = new ImageView[5];
00451     zoomLitBar[0] = (ImageView) findViewById(R.id.zoom_bar_lit_0);
00452     zoomLitBar[1] = (ImageView) findViewById(R.id.zoom_bar_lit_1);
00453     zoomLitBar[2] = (ImageView) findViewById(R.id.zoom_bar_lit_2);
00454     zoomLitBar[3] = (ImageView) findViewById(R.id.zoom_bar_lit_3);
00455     zoomLitBar[4] = (ImageView) findViewById(R.id.zoom_bar_lit_4);
00456 
00457     homeIcon = (ImageView) findViewById(R.id.pt_home_marker);
00458   }
00459 
00460   private void loadSettings() {
00461     // Load the settings from the shared preferences.
00462     SharedPreferences settings =
00463         this.getContext().getSharedPreferences(SHARED_PREFERENCE_NAME, Context.MODE_PRIVATE);
00464     settings.getFloat(MAX_PAN_KEY_NAME, maxPan);
00465     settings.getFloat(MIN_PAN_KEY_NAME, minPan);
00466     settings.getFloat(MAX_TILT_KEY_NAME, maxTilt);
00467     settings.getFloat(MIN_TILT_KEY_NAME, minTilt);
00468     settings.getFloat(HOME_PAN_KEY_NAME, homePan);
00469     settings.getFloat(HOME_TILT_KEY_NAME, homeTilt);
00470   }
00471 
00478   private void publishPan(float x) {
00479     // Normalize the pan value from the current range to (-1:+1).
00480     float pan = 1.0f - (MAX_TACK_COORDINATE - x) / GUIDE_LENGTH;
00481     // Transform the normalized pan value to the pan range for the device.
00482     pan = (maxPan - minPan) * pan + minPan;
00483     // Initialize the message with the pan position value and publish it.
00484     sensor_msgs.JointState jointState = publisher.newMessage();
00485     jointState.getName().add("pan");
00486     jointState.setPosition(new double[] { pan });
00487     publisher.publish(jointState);
00488   }
00489 
00496   private void publishTilt(float y) {
00497     // Normalize the tilt value from the current range to (-1:+1).
00498     float tilt = 1.0f - (MAX_TACK_COORDINATE - y) / GUIDE_LENGTH;
00499     // Transform the normalized tilt value to the pan range for the device.
00500     tilt = (maxTilt - minTilt) * tilt + minTilt;
00501     // Initialize the message with the tilt position value and publish it.
00502     sensor_msgs.JointState jointState = publisher.newMessage();
00503     jointState.getName().add("tilt");
00504     jointState.setPosition(new double[] { tilt });
00505     publisher.publish(jointState);
00506   }
00507 
00508   @Override
00509   public GraphName getDefaultNodeName() {
00510     return GraphName.of("android_15/pan_tilt_view");
00511   }
00512 
00513   @Override
00514   public void onStart(ConnectedNode connectedNode) {
00515     publisher = connectedNode.newPublisher("ptu_cmd", sensor_msgs.JointState._TYPE);
00516   }
00517 
00518   @Override
00519   public void onShutdown(Node node) {
00520   }
00521 
00522   @Override
00523   public void onShutdownComplete(Node node) {
00524   }
00525 
00526   @Override
00527   public void onError(Node node, Throwable throwable) {
00528   }
00529 }


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