public class DistanceView
extends GLSurfaceView
implements org.ros.node.NodeMain, org.ros.message.MessageListener<sensor_msgs.LaserScan>
Constructor and Description |
---|
DistanceView(Context context)
Initialize the rendering surface.
|
DistanceView(Context context,
AttributeSet attrs) |
Modifier and Type | Method and Description |
---|---|
void |
currentSpeed(double speed)
Updates the current speed in
distanceRenderer which then can
adjust the zoom level in velocity mode. |
org.ros.namespace.GraphName |
getDefaultNodeName() |
void |
lockZoom()
Prevents changes to the zoom level.
|
void |
onError(org.ros.node.Node node,
java.lang.Throwable throwable) |
void |
onNewMessage(sensor_msgs.LaserScan message) |
void |
onShutdown(org.ros.node.Node node) |
void |
onShutdownComplete(org.ros.node.Node node) |
void |
onStart(org.ros.node.ConnectedNode connectedNode) |
boolean |
onTouch(View v,
MotionEvent event) |
void |
setTopicName(java.lang.String topicName)
Sets the topic that the distance view node should subscribe to.
|
void |
setZoomMode(ZoomMode mode)
Sets the zoom mode to one of the modes in
ZoomMode . |
void |
unlockZoom()
Unlocks the zoom allowing it to be changed.
|
public DistanceView(Context context)
context
- public DistanceView(Context context, AttributeSet attrs)
public void setTopicName(java.lang.String topicName)
topicName
- Name of the ROS topic.public org.ros.namespace.GraphName getDefaultNodeName()
getDefaultNodeName
in interface org.ros.node.NodeMain
public void onStart(org.ros.node.ConnectedNode connectedNode)
onStart
in interface org.ros.node.NodeListener
public void onShutdown(org.ros.node.Node node)
onShutdown
in interface org.ros.node.NodeListener
public void onShutdownComplete(org.ros.node.Node node)
onShutdownComplete
in interface org.ros.node.NodeListener
public void onError(org.ros.node.Node node, java.lang.Throwable throwable)
onError
in interface org.ros.node.NodeListener
public void onNewMessage(sensor_msgs.LaserScan message)
public void setZoomMode(ZoomMode mode)
ZoomMode
.mode
- The zoom mode that must be set.public void lockZoom()
public void unlockZoom()
public void currentSpeed(double speed)
distanceRenderer
which then can
adjust the zoom level in velocity mode.speed
- The linear velocity of the robot.public boolean onTouch(View v, MotionEvent event)