Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
org.ros.android.view.VirtualJoystickView Class Reference
Inheritance diagram for org.ros.android.view.VirtualJoystickView:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void DisableSnapping ()
void EnableSnapping ()
GraphName getDefaultNodeName ()
void onAnimationEnd (Animation animation)
void onAnimationRepeat (Animation animation)
void onAnimationStart (Animation animation)
void onError (Node node, Throwable throwable)
void onNewMessage (final nav_msgs.Odometry message)
void onShutdown (Node node)
void onShutdownComplete (Node node)
void onStart (ConnectedNode connectedNode)
boolean onTouchEvent (MotionEvent event)
void setHolonomic (boolean enabled)
void setTopicName (String topicName)
 VirtualJoystickView (Context context)
 VirtualJoystickView (Context context, AttributeSet attrs)
 VirtualJoystickView (Context context, AttributeSet attrs, int defStyle)

Protected Member Functions

void onLayout (boolean changed, int l, int t, int r, int b)

Private Member Functions

void animateIntensityCircle (float endScale)
void animateIntensityCircle (float endScale, long duration)
void animateOrientationWidgets ()
float differenceBetweenAngles (float angle0, float angle1)
void endTurnInPlaceRotation ()
boolean floatCompare (float v1, float v2)
void initiateTurnInPlace ()
void initVirtualJoystick (Context context)
boolean inLastContactRange (float x, float y)
void onContactDown ()
void onContactMove (float x, float y)
void onContactUp ()
void publishVelocity (double linearVelocityX, double linearVelocityY, double angularVelocityZ)
void updateMagnitudeText ()
void updateThumbDivet (float x, float y)
void updateTurnInPlaceMode ()
void updateTurnInPlaceRotation ()

Private Attributes

float contactRadius
float contactTheta
Point contactUpLocation
volatile float currentOrientation
ImageView currentRotationRange
geometry_msgs.Twist currentVelocityCommand
float deadZoneRatio = Float.NaN
boolean holonomic
ImageView intensity
float joystickRadius = Float.NaN
ImageView lastVelocityDivet
boolean magnetizedXAxis
float magnetTheta = 10.0f
TextView magnitudeText
RelativeLayout mainLayout
float normalizedMagnitude
float normalizingMultiplier
ImageView[] orientationWidget
float parentSize = Float.NaN
int pointerId = INVALID_POINTER_ID
ImageView previousRotationRange
boolean previousVelocityMode
Publisher< geometry_msgs.Twist > publisher
Timer publisherTimer
volatile boolean publishVelocity
float rightTurnOffset
ImageView thumbDivet
String topicName
volatile boolean turnInPlaceMode
float turnInPlaceStartTheta = Float.NaN

Static Private Attributes

static final float BOX_TO_CIRCLE_RATIO = 1.363636f
static final float FLOAT_EPSILON = 0.001f
static final int INVALID_POINTER_ID = -1
static final float ORIENTATION_TACK_FADE_RANGE = 40.0f
static final float POST_LOCK_MAGNET_THETA = 20.0f
static final float THUMB_DIVET_RADIUS = 16.5f
static final long TURN_IN_PLACE_CONFIRMATION_DELAY = 200L

Detailed Description

VirtualJoystickView creates a virtual joystick view that publishes velocity as (geometry_msgs.Twist) messages. The current version contains the following features: snap to axes, turn in place, and resume previous velocity.

Author:
munjaldesai@google.com (Munjal Desai)

Definition at line 53 of file VirtualJoystickView.java.


Constructor & Destructor Documentation

Definition at line 244 of file VirtualJoystickView.java.

org.ros.android.view.VirtualJoystickView.VirtualJoystickView ( Context  context,
AttributeSet  attrs 
) [inline]

Definition at line 250 of file VirtualJoystickView.java.

org.ros.android.view.VirtualJoystickView.VirtualJoystickView ( Context  context,
AttributeSet  attrs,
int  defStyle 
) [inline]

Definition at line 256 of file VirtualJoystickView.java.


Member Function Documentation

void org.ros.android.view.VirtualJoystickView.animateIntensityCircle ( float  endScale) [inline, private]

Scale and rotate the intensity circle instantaneously. The key difference between this method and animateIntensityCircle(float, long) is that this method does not attach an animation listener and the animation is instantaneous.

Parameters:
endScaleThe scale factor that must be attained at the end of the animation.

Definition at line 435 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.animateIntensityCircle ( float  endScale,
long  duration 
) [inline, private]

Scale and rotate the intensity circle over the specified duration. Unlike animateIntensityCircle(float) this method registers an animation listener.

Parameters:
endScaleThe scale factor that must be attained at the end of the animation.
durationThe duration in milliseconds the animation should take.

Definition at line 467 of file VirtualJoystickView.java.

Fade in and fade out the orientationWidgets. The widget best aligned with the contactTheta will be the brightest and the successive ones within ORIENTATION_TACK_FADE_RANGE the will be faded out proportionally. The tacks out of that range will have alpha set to 0.

Definition at line 498 of file VirtualJoystickView.java.

float org.ros.android.view.VirtualJoystickView.differenceBetweenAngles ( float  angle0,
float  angle1 
) [inline, private]

From http://actionsnippet.com/?p=1451. Calculates the difference between 2 angles. The result is always the minimum difference between 2 angles (0< result <= 360).

Parameters:
angle0One of 2 angles used to calculate difference. The order of arguments does not matter. Must be in degrees.
angle1One of 2 angles used to calculate difference. The order of arguments does not matter. Must be in degrees.
Returns:
The difference between the 2 arguments in degrees.

Definition at line 523 of file VirtualJoystickView.java.

Allows the user the option to turn off the auto-snap feature.

Definition at line 387 of file VirtualJoystickView.java.

Allows the user the option to turn on the auto-snap feature.

Definition at line 380 of file VirtualJoystickView.java.

Sets turnInPlaceMode to false indicating that the turn-in-place is no longer active. It also changes the alpha values appropriately.

Definition at line 531 of file VirtualJoystickView.java.

boolean org.ros.android.view.VirtualJoystickView.floatCompare ( float  v1,
float  v2 
) [inline, private]

Comparing 2 float values.

Parameters:
v1
v2
Returns:
True if v1 and v2 and within { FLOAT_EPSILON} of each other. False otherwise.

Definition at line 906 of file VirtualJoystickView.java.

Implements org::ros::node::NodeMain.

Definition at line 928 of file VirtualJoystickView.java.

Called each time turn-in-place mode is initiated.

Definition at line 815 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.initVirtualJoystick ( Context  context) [inline, private]

Sets up the visual elements of the virtual joystick.

Definition at line 541 of file VirtualJoystickView.java.

boolean org.ros.android.view.VirtualJoystickView.inLastContactRange ( float  x,
float  y 
) [inline, private]

Definition at line 914 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.onAnimationEnd ( Animation  animation) [inline]

Definition at line 272 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.onAnimationRepeat ( Animation  animation) [inline]

Definition at line 279 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.onAnimationStart ( Animation  animation) [inline]

Definition at line 283 of file VirtualJoystickView.java.

Update the virtual joystick to indicate a contact down has occurred.

Definition at line 606 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.onContactMove ( float  x,
float  y 
) [inline, private]

Updates the virtual joystick layout based on the location of the contact. Generates the velocity messages. Switches in and out of turn-in-place.

Parameters:
xThe x coordinates of the contact relative to the parent container.
yThe y coordinates of the contact relative to the parent container.

Definition at line 629 of file VirtualJoystickView.java.

The divets and the ring are made transparent to reflect that the virtual joystick is no longer active. The intensity circle is slowly scaled to 0.

Definition at line 763 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.onError ( Node  node,
Throwable  throwable 
) [inline]

Implements org::ros::node::NodeListener.

Definition at line 961 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.onLayout ( boolean  changed,
int  l,
int  t,
int  r,
int  b 
) [inline, protected]

Initialize the fields with values that can only be determined once the layout for the views has been determined.

Definition at line 396 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.onNewMessage ( final nav_msgs.Odometry  message) [inline]

Definition at line 287 of file VirtualJoystickView.java.

Implements org::ros::node::NodeListener.

Definition at line 951 of file VirtualJoystickView.java.

Implements org::ros::node::NodeListener.

Definition at line 955 of file VirtualJoystickView.java.

Implements org::ros::node::NodeListener.

Definition at line 933 of file VirtualJoystickView.java.

boolean org.ros.android.view.VirtualJoystickView.onTouchEvent ( MotionEvent  event) [inline]

Definition at line 313 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.publishVelocity ( double  linearVelocityX,
double  linearVelocityY,
double  angularVelocityZ 
) [inline, private]

Publish the velocity as a ROS Twist message.

Parameters:
linearVelocityXThe normalized linear velocity (-1 to 1).
angularVelocityZThe normalized angular velocity (-1 to 1).

Definition at line 802 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.setHolonomic ( boolean  enabled) [inline]
Parameters:
enabled
 true 
if this joystick should publish linear velocities along the Y axis instead of angular velocities along the Z axis,
 false 
otherwise

Definition at line 267 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.setTopicName ( String  topicName) [inline]

Definition at line 923 of file VirtualJoystickView.java.

Update the linear velocity text view.

Definition at line 835 of file VirtualJoystickView.java.

void org.ros.android.view.VirtualJoystickView.updateThumbDivet ( float  x,
float  y 
) [inline, private]

Moves the thumbDivet to the specified coordinates (under the contact) and also orients it so that is facing the direction opposite to the center of the mainLayout.

Parameters:
xThe x coordinate relative to the center of the mainLayout
yThe Y coordinate relative to the center of the mainLayout

Definition at line 887 of file VirtualJoystickView.java.

Enable/Disable turn-in-place mode.

Definition at line 714 of file VirtualJoystickView.java.

Based on the difference between the current orientation and the orientation when the turn-in-place mode was initiated, update the visuals.

Definition at line 850 of file VirtualJoystickView.java.


Member Data Documentation

final float org.ros.android.view.VirtualJoystickView.BOX_TO_CIRCLE_RATIO = 1.363636f [static, private]

BOX_TO_CIRCLE_RATIO The dimensions of the square box that contains the circle, rings, etc are 300x300. The circles, rings, etc have a diameter of 220. The ratio of the box to the circles is 300/220 = 1.363636. This ratio stays the same regardless of the size of the virtual joystick.

Definition at line 62 of file VirtualJoystickView.java.

contactRadius This is the distance between the center of the widget and the point of contact normalized between 0 and 1. This is mostly used for animation/display calculations.

TODO(munjaldesai): Omnigraffle this for better documentation.

Definition at line 148 of file VirtualJoystickView.java.

contactTheta The current orientation of the virtual joystick in degrees.

Definition at line 134 of file VirtualJoystickView.java.

contactUpLocation The location of the primary contact when it is lifted off of the screen.

Definition at line 216 of file VirtualJoystickView.java.

currentOrientation The orientation of the robot in degrees.

Definition at line 206 of file VirtualJoystickView.java.

currentRotationRange The (15 degree) green slice/arc used to indicate turn-in-place behavior.

Definition at line 181 of file VirtualJoystickView.java.

Definition at line 241 of file VirtualJoystickView.java.

deadZoneRatio ...

TODO(munjaldesai): Write a simple explanation for this. Currently not easy to immediately comprehend it's meaning.

TODO(munjaldesai): Omnigraffle this for better documentation.

Definition at line 157 of file VirtualJoystickView.java.

final float org.ros.android.view.VirtualJoystickView.FLOAT_EPSILON = 0.001f [static, private]

FLOAT_EPSILON Used for comparing float values.

Definition at line 83 of file VirtualJoystickView.java.

 true 

if the joystick should publish linear velocities along the Y axis instead of angular velocities along the Z axis,

 false 

otherwise.

Definition at line 231 of file VirtualJoystickView.java.

intensity The intensity circle that is used to show the current magnitude.

Definition at line 106 of file VirtualJoystickView.java.

Definition at line 96 of file VirtualJoystickView.java.

joystickRadius The center coordinates of the parent layout holding all the elements of the virtual joystick. The coordinates are relative to the immediate parent (mainLayout). Since the parent must be a square centerX = centerY = radius.

Definition at line 164 of file VirtualJoystickView.java.

lastVelocityDivet The divet that shows the location of last contact. If a contact is placed within (THUMB_DIVET_RADIUS) to this, the previousVelocityMode is triggered.

Definition at line 118 of file VirtualJoystickView.java.

magnetizedXAxis True when the contact has been snapped to the x-axis, false otherwise.

Definition at line 225 of file VirtualJoystickView.java.

MAGNET_THETA The number of degrees before and after the major axes (0, 90, 180, and 270) where the orientation is automatically adjusted to 0, 90, 180, or 270. For example, if the contactTheta is 85 degrees and MAGNET_THETA is 10, the contactTheta will be changed to 90.

Definition at line 69 of file VirtualJoystickView.java.

magnitudeIndicator Shows the current linear velocity as a percent value. This TextView will be on the opposite side of the contact to ensure that is it visible most of the time. The font size and distance from the center of the widget are automatically computed based on the size of parent container.

Definition at line 132 of file VirtualJoystickView.java.

mainLayout The parent layout that contains all the elements of the virtual joystick.

Definition at line 102 of file VirtualJoystickView.java.

normalizedMagnitude This is the distance between the center divet and the point of contact normalized between 0 and 1. The linear velocity is based on this.

Definition at line 140 of file VirtualJoystickView.java.

normalizingMultiplier Used to convert any distance from pixels to a normalized value between 0 and 1. 0 is the center of widget and 1 is the normalized distance to the outerRing from the center of the widget.

Definition at line 176 of file VirtualJoystickView.java.

ORIENTATION_TACK_FADE_RANGE The range in degrees around the current orientation where the orientationWidgets will be visible.

Definition at line 74 of file VirtualJoystickView.java.

orientationWidget 4 long tacks on the major axes and 20 small tacks off of the major axes at 15 degree increments. These fade in and fade out to collectively indicate the current orientation.

Definition at line 124 of file VirtualJoystickView.java.

parentSize The length (width==height ideally) of a side of the parent container that holds the virtual joystick.

Definition at line 169 of file VirtualJoystickView.java.

pointerId Used to keep track of the contact that initiated the interaction with the virtual joystick. All other contacts are ignored.

Definition at line 211 of file VirtualJoystickView.java.

POST_LOCK_MAGNET_THETA Replaces magnetTheta once the contact has been magnetized/snapped around 90/270.

Definition at line 95 of file VirtualJoystickView.java.

previousRotationRange The (30 degree) green slice/arc used to indicate turn-in-place behavior.

Definition at line 186 of file VirtualJoystickView.java.

previousVelocityMode True when the new contact position is within

Definition at line 220 of file VirtualJoystickView.java.

Publisher<geometry_msgs.Twist> org.ros.android.view.VirtualJoystickView.publisher [private]

Definition at line 97 of file VirtualJoystickView.java.

Used to publish velocity commands at a specific rate.

Definition at line 240 of file VirtualJoystickView.java.

Velocity commands are published when this is true. Not published otherwise. This is to prevent spamming velocity commands.

Definition at line 236 of file VirtualJoystickView.java.

rightTurnOffset The rotation offset in degrees applied to currentRotationRange and previousRotationRange when the robot is turning clockwise (right) in turn-in-place mode.

Definition at line 202 of file VirtualJoystickView.java.

final float org.ros.android.view.VirtualJoystickView.THUMB_DIVET_RADIUS = 16.5f [static, private]

THUMB_DIVET_RADIUS The radius of the thumbDivet. This is also the distance threshold around the contactUpLocation that triggers the previous-velocity-mode previousVelocityMode. This radius is also the same for the lastVelocityDivet.

Definition at line 90 of file VirtualJoystickView.java.

thumbDivet The divet that is underneath the user's thumb. When there is no contact it moves to the center (over the center divet). An arrow inside it is used to indicate the orientation.

Definition at line 112 of file VirtualJoystickView.java.

Definition at line 242 of file VirtualJoystickView.java.

TURN_IN_PLACE_CONFIRMATION_DELAY Time (in milliseconds) to wait before visually changing to turn-in-place mode.

Definition at line 79 of file VirtualJoystickView.java.

turnInPlaceMode True when the virtual joystick is in turn-in-place mode. False otherwise.

Definition at line 191 of file VirtualJoystickView.java.

turnInPlaceStartTheta The orientation of the robot when the turn-in-place mode is initiated.

Definition at line 196 of file VirtualJoystickView.java.


The documentation for this class was generated from the following file:


android_core
Author(s): Damon Kohler
autogenerated on Thu Aug 27 2015 12:11:33