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

List of all members.

Public Member Functions

GraphName getDefaultNodeName ()
void onError (Node node, Throwable throwable)
void onShutdown (Node node)
void onShutdownComplete (Node node)
void onStart (ConnectedNode connectedNode)
boolean onTouch (View v, MotionEvent event)
 PanTiltView (Context context)
 PanTiltView (Context context, AttributeSet attrs)
 PanTiltView (Context context, AttributeSet attrs, int defStyle)

Private Member Functions

void initPanTiltWidget ()
void loadSettings ()
void onContactDown (float x, float y)
void onContactMove (float x, float y)
void publishPan (float x)
void publishTilt (float y)
void updateRightTack (float y)
void updateTopTack (float x)
void updateZoomBars ()

Private Attributes

ImageView desiredTack
ImageView homeIcon
float homePan = 0f
float homeTilt = 0f
int initialPointerLocation
RelativeLayout mainLayout
float maxPan = 1.0f
float maxTilt = 1.0f
float minPan = -1.0f
float minTilt = -1.0f
int pointerId = INVALID_POINTER_ID
Publisher< sensor_msgs.JointState > publisher
ImageView[] rightLargeTack
ImageView[] rightSmallTack
ImageView[] topLargeTack
ImageView[] topSmallTack
ImageView[] zoomLitBar
int zoomValue = 0

Static Private Attributes

static final float GUIDE_LENGTH = (MAX_TACK_COORDINATE - MIN_TACK_COORDINATE)
static final String HOME_PAN_KEY_NAME = "HOME_PAN"
static final String HOME_TILT_KEY_NAME = "HOME_TILT"
static final int INVALID_POINTER_ID = -1
static final int INVALID_POINTER_LOCATION = -1
static final String MAX_PAN_KEY_NAME = "MAX_PAN"
static final int MAX_TACK_COORDINATE = 184
static final String MAX_TILT_KEY_NAME = "MAX_TILT"
static final int MIDDLE_AREA = 0
static final String MIN_PAN_KEY_NAME = "MIN_PAN"
static final int MIN_TACK_COORDINATE = 35
static final String MIN_TILT_KEY_NAME = "MIN_TILT"
static final int RIGHT_AREA = 2
static final String SHARED_PREFERENCE_NAME = "PAN_TILT_VIEW_PREFERENCE"
static final int TOP_AREA = 1

Detailed Description

PanTiltZoomView creates a rosjava view that can be used to control a pan tilt device.

Author:
munjaldesai@google.com (Munjal Desai)

Definition at line 41 of file PanTiltView.java.


Constructor & Destructor Documentation

org.ros.android.view.PanTiltView.PanTiltView ( Context  context) [inline]

Definition at line 147 of file PanTiltView.java.

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

Definition at line 151 of file PanTiltView.java.

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

Definition at line 155 of file PanTiltView.java.


Member Function Documentation

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

Definition at line 509 of file PanTiltView.java.

Definition at line 392 of file PanTiltView.java.

Definition at line 460 of file PanTiltView.java.

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

Calls the necessary methods to update the value(s) (pan and/or tilt). Also sets the initial location based on the location of the DOWN event.

Parameters:
xThe x coordinate of the pointer relative to the parent.
yThe y coordinate of the pointer relative to the parent.

Definition at line 248 of file PanTiltView.java.

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

Calls the necessary methods to update the value(s) (pan and/or tilt) based on the pointer's initial location.

Parameters:
xThe x coordinate of the pointer relative to the parent.
yThe y coordinate of the pointer relative to the parent.

Definition at line 207 of file PanTiltView.java.

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

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

Definition at line 527 of file PanTiltView.java.

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

Definition at line 519 of file PanTiltView.java.

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

Definition at line 523 of file PanTiltView.java.

void org.ros.android.view.PanTiltView.onStart ( ConnectedNode  connectedNode) [inline]

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

Definition at line 514 of file PanTiltView.java.

boolean org.ros.android.view.PanTiltView.onTouch ( View  v,
MotionEvent  event 
) [inline]

Definition at line 165 of file PanTiltView.java.

void org.ros.android.view.PanTiltView.publishPan ( float  x) [inline, private]

Publish the pan position.

Parameters:
xthe x coordinate corrected for the tack size, but not normalized

Definition at line 478 of file PanTiltView.java.

void org.ros.android.view.PanTiltView.publishTilt ( float  y) [inline, private]

Publish the tilt position.

Parameters:
ythe y coordinate corrected for the tack size, but not normalized

Definition at line 496 of file PanTiltView.java.

void org.ros.android.view.PanTiltView.updateRightTack ( float  y) [inline, private]

Updates the location of the tilt tack on the right and the center tack. It also calls publishTilt(float).

Parameters:
yThe y coordinate of the pointer relative to the bottom of the parent.

Definition at line 311 of file PanTiltView.java.

void org.ros.android.view.PanTiltView.updateTopTack ( float  x) [inline, private]

Updates the location of the pan tack on the top and the center tack. It also calls publishPan(float).

Parameters:
xThe x coordinate of the pointer relative to the parent.

Definition at line 353 of file PanTiltView.java.

Definition at line 293 of file PanTiltView.java.


Member Data Documentation

Definition at line 103 of file PanTiltView.java.

GUIDE_LENGTH The length of the pan and tilt guides in pixels. This values is used to normalize the coordinates to -1:+1.

Definition at line 83 of file PanTiltView.java.

final String org.ros.android.view.PanTiltView.HOME_PAN_KEY_NAME = "HOME_PAN" [static, private]

Definition at line 89 of file PanTiltView.java.

final String org.ros.android.view.PanTiltView.HOME_TILT_KEY_NAME = "HOME_TILT" [static, private]

Definition at line 90 of file PanTiltView.java.

Definition at line 104 of file PanTiltView.java.

homePan The pan value for the home position for the pan tilt device.

Definition at line 134 of file PanTiltView.java.

homeTilt The tilt value for the home position for the pan tilt device.

Definition at line 138 of file PanTiltView.java.

initialPointerLocation Remembers the location where DOWN occurred for the active pointer. Possible values are MIDDLE_AREA, TOP_AREA , and RIGHT_AREA.

Definition at line 110 of file PanTiltView.java.

final int org.ros.android.view.PanTiltView.INVALID_POINTER_ID = -1 [static, private]

Definition at line 43 of file PanTiltView.java.

Definition at line 44 of file PanTiltView.java.

mainLayout The parent layout that contains all other elements.

Definition at line 97 of file PanTiltView.java.

final String org.ros.android.view.PanTiltView.MAX_PAN_KEY_NAME = "MAX_PAN" [static, private]

Definition at line 86 of file PanTiltView.java.

final int org.ros.android.view.PanTiltView.MAX_TACK_COORDINATE = 184 [static, private]

MAX_TACK_COORDINATE The maximum padding used by panTack and tiltTack.

Definition at line 78 of file PanTiltView.java.

final String org.ros.android.view.PanTiltView.MAX_TILT_KEY_NAME = "MAX_TILT" [static, private]

Definition at line 88 of file PanTiltView.java.

maxPan The maximum pan value for the pan tilt device being controlled. By default the pan range is normalized from -1 (left) to 1 (right).

Definition at line 120 of file PanTiltView.java.

maxTilt The maximum tilt value for the pan tilt device being controlled. By default the tilt range is normalized from -1 (down) to 1 (up).

Definition at line 130 of file PanTiltView.java.

final int org.ros.android.view.PanTiltView.MIDDLE_AREA = 0 [static, private]

MIDDLE_AREA This, RIGHT_AREA, and TOP_AREA are values that represent the section of the view where the POINTER_DOWN event occurred. The MIDDLE_AREA represents the area below the top guide (pan marker) and left of the right guide (tilt marker).

TODO(munjaldesai): Since these 3 values are used very often, replace the logic with bitwise operations.

Definition at line 54 of file PanTiltView.java.

final String org.ros.android.view.PanTiltView.MIN_PAN_KEY_NAME = "MIN_PAN" [static, private]

Definition at line 85 of file PanTiltView.java.

final int org.ros.android.view.PanTiltView.MIN_TACK_COORDINATE = 35 [static, private]

MIN_TACK_COORDINATE The minimum padding used by panTack and tiltTack.

Definition at line 73 of file PanTiltView.java.

final String org.ros.android.view.PanTiltView.MIN_TILT_KEY_NAME = "MIN_TILT" [static, private]

Definition at line 87 of file PanTiltView.java.

float org.ros.android.view.PanTiltView.minPan = -1.0f [private]

minPan The minimum pan value for the pan tilt device being controlled. By default the pan range is normalized from -1 (left) to 1 (right).

Definition at line 115 of file PanTiltView.java.

minTilt The minimum tilt value for the pan tilt device being controlled. By default the tilt range is normalized from -1 (down) to 1 (up).

Definition at line 125 of file PanTiltView.java.

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

Definition at line 143 of file PanTiltView.java.

Publisher<sensor_msgs.JointState> org.ros.android.view.PanTiltView.publisher [private]

Definition at line 92 of file PanTiltView.java.

final int org.ros.android.view.PanTiltView.RIGHT_AREA = 2 [static, private]

RIGHT_AREA This, MIDDLE_AREA, and TOP_AREA are values that represent the section of the view where the POINTER_DOWN event occurred. The RIGHT_AREA represents the area to the right of right guide (tilt marker).

Definition at line 68 of file PanTiltView.java.

Definition at line 100 of file PanTiltView.java.

Definition at line 101 of file PanTiltView.java.

final String org.ros.android.view.PanTiltView.SHARED_PREFERENCE_NAME = "PAN_TILT_VIEW_PREFERENCE" [static, private]

Definition at line 84 of file PanTiltView.java.

final int org.ros.android.view.PanTiltView.TOP_AREA = 1 [static, private]

TOP_AREA This, MIDDLE_AREA, and RIGHT_AREA are values that represent the section of the view where the POINTER_DOWN event occurred. The TOP_AREA represents the area above the top guide (pan marker).

Definition at line 61 of file PanTiltView.java.

Definition at line 98 of file PanTiltView.java.

Definition at line 99 of file PanTiltView.java.

Definition at line 102 of file PanTiltView.java.

Definition at line 145 of file PanTiltView.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