Skip navigation links
A B C D E F G H I J K L M N O P Q R S T U V W X Y Z _ 

A

A - Variable in class lejos.hardware.device.PFMate
 
A - Variable in class lejos.hardware.device.RCXLink
 
A - Variable in class lejos.hardware.device.RCXMotorMultiplexer
 
A - Static variable in class lejos.hardware.motor.Motor
Motor A.
A - Static variable in interface lejos.hardware.port.MotorPort
MotorPort A.
AbstractCalibrationFilter - Class in lejos.robotics.filter
 
AbstractCalibrationFilter(SampleProvider) - Constructor for class lejos.robotics.filter.AbstractCalibrationFilter
 
AbstractCalibrationFilter.CalibrationFileException - Exception in lejos.robotics.filter
 
AbstractFilter - Class in lejos.robotics.filter
Base class for Sample filters
AbstractFilter(SampleProvider) - Constructor for class lejos.robotics.filter.AbstractFilter
 
ACCEL_DATA - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
Accel_I2C_address - Variable in class lejos.hardware.sensor.DexterIMUSensor
 
acceleration - Variable in class lejos.hardware.motor.BaseRegulatedMotor
 
Accelerometer - Interface in lejos.robotics
Interface for Acceleration sensors
AccelerometerAdapter - Class in lejos.robotics
 
AccelerometerAdapter(SampleProvider) - Constructor for class lejos.robotics.AccelerometerAdapter
 
accelMode - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
action() - Method in interface lejos.robotics.subsumption.Behavior
The code in action() represents the tasks the robot performs when this behavior becomes active.
activate() - Method in interface lejos.hardware.port.LegacySensorPort
 
ADC_REF - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
ADC_RES - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
add(Point) - Method in class lejos.robotics.geometry.Point
Returns the vector sum of this and other
addDCMotor(int, String) - Method in class lejos.hardware.device.LSC
Method to add a DC Motor
addDCMotor(int, String, int, int, int, int) - Method in class lejos.hardware.device.LSC
Method to add a DC Motor
addDetector(FeatureDetector) - Method in class lejos.robotics.objectdetection.FusorDetector
This method adds another FeatureDetector to the FusorDetector.
addFeatureDetector(FeatureDetector) - Method in class lejos.robotics.mapping.EV3NavigationModel
Add a feature detector to the model
addKeyListener(KeyListener) - Method in interface lejos.hardware.Key
 
addKeyListener(KeyListener) - Method in class lejos.remote.ev3.RemoteKey
 
addKeyListener(KeyListener) - Method in class lejos.remote.ev3.RemoteRequestKey
 
addKeyListener(KeyListener) - Method in interface lejos.remote.ev3.RMIKey
 
addKeyListener(KeyListener) - Method in class lejos.remote.ev3.RMIRemoteKey
 
addListener(RegulatedMotorListener) - Method in class lejos.hardware.device.MMXRegulatedMotor
 
addListener(RegulatedMotorListener) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
addListener(GPSListener) - Static method in class lejos.hardware.gps.SimpleGPS
add a listener to manage events with GPS
addListener(RegulatedMotorListener) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Add a motor listener.
addListener(RegulatedMotor, RegulatedMotorListener) - Method in class lejos.hardware.motor.JavaMotorRegulator
 
addListener(RegulatedMotor, RegulatedMotorListener) - Method in interface lejos.hardware.motor.MotorRegulator
Add a motor listener.
addListener(RegulatedMotorListener) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
addListener(RegulatedMotorListener) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Adds a listener object that will be notified when rotation has started or stopped
addListener(RegulatedMotorListener) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
addListener(NavEventListener) - Method in class lejos.robotics.mapping.EV3NavigationModel
 
addListener(RegulatedMotorListener) - Method in class lejos.robotics.MirrorMotor
 
addListener(FeatureListener) - Method in interface lejos.robotics.objectdetection.FeatureDetector
Adds a listener to the FeatureDetector.
addListener(FeatureListener) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
addListener(FeatureListener) - Method in class lejos.robotics.objectdetection.FusorDetector
 
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.NodePathFinder
 
addListener(WaypointListener) - Method in interface lejos.robotics.pathfinding.PathFinder
 
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.RandomPathFinder
 
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
addListener(RegulatedMotorListener) - Method in interface lejos.robotics.RegulatedMotor
Adds a listener object that will be notified when rotation has started or stopped
addLSC(int) - Method in class lejos.hardware.device.NXTe
Add a LSC, Lattebox Servo Controller
addMessageListener(LCPMessageListener) - Static method in class lejos.remote.nxt.LCP
Add a listener for incoming LCP messages.
addMoveListener(MoveListener) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
addMoveListener(MoveListener) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
addMoveListener(MoveListener) - Method in class lejos.robotics.navigation.MovePilot
 
addMoveListener(MoveListener) - Method in interface lejos.robotics.navigation.MoveProvider
Adds a MoveListener that will be notified of all movement events.
addMoveListener(MoveListener) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
addMoveListener(MoveListener) - Method in class lejos.robotics.navigation.SteeringPilot
 
addNavigationListener(NavigationListener) - Method in class lejos.robotics.navigation.Navigator
Adds a NavigationListener that is informed when a the robot stops or reaches a WayPoint.
addNavigator(Navigator) - Method in class lejos.robotics.mapping.EV3NavigationModel
Add a navigator to the model
addNeighbor(Node) - Method in class lejos.robotics.pathfinding.Node
Adds a neighboring node to this node, connecting them together.
addNode(Node, int) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Adds a node to this set and connects it with a number of neighboring nodes.
addNode(Node, int) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Adds a node to this set and connects it with a number of neighboring nodes.
addPilot(MoveController) - Method in class lejos.robotics.mapping.EV3NavigationModel
Add a pilot to the model
addPoseProvider(PoseProvider) - Method in class lejos.robotics.mapping.EV3NavigationModel
Add a pose provider (which might be MCL) to the model
addRangeScanner(RangeScanner) - Method in class lejos.robotics.mapping.EV3NavigationModel
Add a range scanner to the model
addReading(double) - Method in class lejos.utility.Integration
Add a new reading and return the current integral
address - Variable in class lejos.hardware.sensor.I2CSensor
 
ADDRESS_LEN - Static variable in class lejos.remote.nxt.NXTCommDevice
 
addressToString(byte[]) - Static method in class lejos.remote.nxt.NXTCommDevice
Helper method to convert address byte array to String.
addServo(int, String) - Method in class lejos.hardware.device.LSC
Method to add a RC servo to current LSC
addServo(int, String, int, int) - Method in class lejos.hardware.device.LSC
Method to add a RC servo to current LSC
addWaypoint(Waypoint) - Method in class lejos.robotics.mapping.EV3NavigationModel
Send a waypoint generated on the NXT to the PC
addWaypoint(Waypoint) - Method in class lejos.robotics.navigation.Navigator
Adds a Waypoint to the end of the path.
addWaypoint(float, float) - Method in class lejos.robotics.navigation.Navigator
Constructs an new Waypoint from the parameters and adds it to the end of the path.
addWaypoint(float, float, float) - Method in class lejos.robotics.navigation.Navigator
Constructs an new Waypoint from the parameters and adds it to the end of the path.
addWaypoint(Waypoint) - Method in interface lejos.robotics.navigation.WaypointListener
Called when the class providing waypoints generates a new waypoint.
addWith(Point) - Method in class lejos.robotics.geometry.Point
Vector addition; add other to this
adjustAcceleration(int) - Method in class lejos.hardware.motor.JavaMotorRegulator
The target acceleration has been changed.
adjustAcceleration(int) - Method in interface lejos.hardware.motor.MotorRegulator
The target acceleration has been changed.
adjustSpeed(float) - Method in class lejos.hardware.motor.JavaMotorRegulator
The target speed has been changed.
adjustSpeed(float) - Method in interface lejos.hardware.motor.MotorRegulator
The target speed has been changed.
allChannelsOff() - Method in class lejos.hardware.device.RCXSensorMultiplexer
Turns off all channels
ANALOG_ID_VAR - Static variable in class lejos.hardware.device.DeviceIdentifier
 
AnalogPort - Interface in lejos.hardware.port
An abstraction for a port that supports Analog/Digital sensors.
AnalogSensor - Class in lejos.hardware.sensor
Base class for analog sensor drivers
AnalogSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.AnalogSensor
 
AnalogSensor(Port, int, int) - Constructor for class lejos.hardware.sensor.AnalogSensor
 
AnalogSensor(Port) - Constructor for class lejos.hardware.sensor.AnalogSensor
 
ANGLE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
angle - Variable in class lejos.robotics.chassis.WheeledChassis.Modeler
 
angle() - Method in class lejos.robotics.geometry.Point
returns the angle in radians of this point from the origin.
angleMode - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
angles - Variable in class lejos.robotics.FixedRangeScanner
 
angles - Variable in class lejos.robotics.RotatingRangeScanner
 
ANGLESTEPSMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
angleTo(Point) - Method in class lejos.robotics.geometry.Point
Returns the direction angle from this point to the Point p
angleTo(Point) - Method in class lejos.robotics.navigation.Pose
Returns the angle with respect to the X axis to
angularAcceleration - Variable in class lejos.robotics.chassis.WheeledChassis
 
angularSpeed - Variable in class lejos.robotics.chassis.WheeledChassis
 
APPEND_NOT_POSSIBLE - Static variable in class lejos.remote.nxt.ErrorMessages
 
applyMove(Move, float, float) - Method in class lejos.robotics.localization.MCLParticle
Apply the robot's move to the particle with a bit of random noise.
applyMove(Move) - Method in class lejos.robotics.localization.MCLParticleSet
Apply a move to each particle
Arbitrator - Class in lejos.robotics.subsumption
An Arbitrator object manages a behavior control system by starting and stopping individual behaviors
by the calling the action() and suppress() methods on them.
Arbitrator(Behavior[], boolean) - Constructor for class lejos.robotics.subsumption.Arbitrator
Allocates an Arbitrator object and initializes it with an array of Behavior objects.
Arbitrator(Behavior[]) - Constructor for class lejos.robotics.subsumption.Arbitrator
Same as Arbitrator(behaviorList, false) Arbitrator start() never exits
arc(double, double, boolean) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
arc(double, double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
arc(double, double) - Method in interface lejos.robotics.chassis.Chassis
Moves the chassis in an arc
arc(double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
arc(double, double) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving.
arc(double, double, boolean) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving.
arc(double, double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
arc(double, double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
arc(double, double) - Method in class lejos.robotics.navigation.MovePilot
 
arc(double, double, boolean) - Method in class lejos.robotics.navigation.MovePilot
 
arc(double, double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
arc(double, double, double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
This method moves the robot in an arc, similar to the other OmniPilot.arc(double, double) methods, except you can choose any of the 360 degree directions relative to the current heading (0) of the robot, while keeping the heading of the robot pointed in the same direction during the move.
arc(double, double, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
arc(double, double, double, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
This method moves the robot in an arc, similar to the other OmniPilot.arc(double, double) methods, except you can choose any of the 360 degree directions relative to the current heading (0) of the robot, while keeping the heading of the robot pointed in the same direction during the move.
arc(double, double) - Method in class lejos.robotics.navigation.SteeringPilot
 
arc(double, double, boolean) - Method in class lejos.robotics.navigation.SteeringPilot
 
ArcAlgorithms - Class in lejos.robotics.navigation
The static methods in this class can be used to to calculate theoretical routes and for displaying graphical representations of the path of a robot.
arcBackward(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
arcBackward(double) - Method in interface lejos.robotics.navigation.ArcMoveController
Starts the NXT robot moving backward along an arc with a specified radius.
arcBackward(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
arcBackward(double) - Method in class lejos.robotics.navigation.MovePilot
 
arcBackward(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
arcBackward(double) - Method in class lejos.robotics.navigation.SteeringPilot
 
arcForward(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
arcForward(double) - Method in interface lejos.robotics.navigation.ArcMoveController
Starts the NXT robot moving forward along an arc with a specified radius.
arcForward(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
arcForward(double) - Method in class lejos.robotics.navigation.MovePilot
 
arcForward(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
arcForward(double) - Method in class lejos.robotics.navigation.SteeringPilot
 
ArcMoveController - Interface in lejos.robotics.navigation
An enhanced MoveController that is capable of traveling in arcs.
ArcRotateMoveController - Interface in lejos.robotics.navigation
A MoveController for robots that can perform arcs and rotate on the spot.
arcUpdate(float, float) - Method in class lejos.robotics.navigation.Pose
Sets the pose location and heading to the correct values resulting from travel in a circular arc.
arrayLeftDivide(Matrix) - Method in class lejos.utility.Matrix
Element-by-element left division, C = A.\B
arrayLeftDivideEquals(Matrix) - Method in class lejos.utility.Matrix
Element-by-element left division in place, A = A.\B
arrayRightDivide(Matrix) - Method in class lejos.utility.Matrix
Element-by-element right division, C = A./B
arrayRightDivideEquals(Matrix) - Method in class lejos.utility.Matrix
Element-by-element right division in place, A = A./B
arrayTimes(Matrix) - Method in class lejos.utility.Matrix
Element-by-element multiplication, C = A.*B
arrayTimesEquals(Matrix) - Method in class lejos.utility.Matrix
 
arrMotorLoad - Static variable in class lejos.hardware.device.LMotor
 
arrMotorUnload - Static variable in class lejos.hardware.device.LMotor
 
ASCENDING - Static variable in interface lejos.hardware.Sounds
 
AsciizCodec - Class in lejos.remote.nxt
Methods to encode and decode ASCIIZ.
AstarSearchAlgorithm - Class in lejos.robotics.pathfinding
This is an implementation of the A* search algorithm.
AstarSearchAlgorithm() - Constructor for class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
asyncRefresh() - Static method in class lejos.hardware.lcd.LCD
Start the process of updating the display.
asyncRefreshWait() - Static method in class lejos.hardware.lcd.LCD
Wait for the current refresh cycle to complete.
atEndOfLine(Line) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
test if this Node is one of the ends of theLine
ATTEMPTED_TO_ACCESS_INVALID_FIELD_OF_A_STRUCTURE - Static variable in class lejos.remote.nxt.ErrorMessages
 
atWaypoint(Waypoint, Pose, int) - Method in class lejos.robotics.mapping.EV3NavigationModel
Called when a waypoint has been reached
atWaypoint(Waypoint, Pose, int) - Method in interface lejos.robotics.navigation.NavigationListener
Called when the robot has reached a new Wahpoint.
Audio - Interface in lejos.hardware
 
audio - Variable in class lejos.hardware.ev3.LocalEV3
 
audio - Static variable in class lejos.hardware.Sound
 
authenticate(String, String) - Method in class lejos.hardware.LocalBTDevice
Authenticate/pair the local device with the specified device
authenticate(String) - Method in class lejos.hardware.RemoteBTDevice
 
autoSendPose - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
available() - Method in class lejos.remote.nxt.NXTInputStream
returns the number of bytes in the input buffer - can be read without blocking
AzimuthFilter - Class in lejos.robotics.filter
This class fails to build at the moment (because there is no code.
AzimuthFilter() - Constructor for class lejos.robotics.filter.AzimuthFilter
 
azimuthTo(Coordinates) - Method in class lejos.hardware.gps.Coordinates
Calculates the azimuth between the two points according to the ellipsoid model of WGS84.

B

B - Variable in class lejos.hardware.device.PFMate
 
B - Variable in class lejos.hardware.device.RCXLink
 
B - Variable in class lejos.hardware.device.RCXMotorMultiplexer
 
B - Static variable in class lejos.hardware.motor.Motor
Motor B.
B - Static variable in interface lejos.hardware.port.MotorPort
MotorPort B.
backward() - Method in class lejos.hardware.device.LServo
Classic backward method for continous RC Servos
backward() - Method in class lejos.hardware.device.MMXMotor
 
backward() - Method in class lejos.hardware.device.PFMateMotor
Runs the motor backward
backward(int) - Method in class lejos.hardware.device.RCXLink
 
backward() - Method in class lejos.hardware.device.tetrix.TetrixMotor
 
backward() - Method in class lejos.hardware.motor.BaseRegulatedMotor
 
backward() - Method in class lejos.hardware.motor.BasicMotor
Causes motor to rotate backwards.
BACKWARD - Static variable in interface lejos.hardware.port.BasicMotorPort
Motor is running backwards
backward() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
backward() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
backward() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
 
backward() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
backward() - Method in interface lejos.robotics.BaseMotor
Causes motor to rotate backwards until stop() or flt() is called.
backward() - Method in class lejos.robotics.MirrorMotor
 
backward() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Starts the NXT robot moving backward.
backward() - Method in interface lejos.robotics.navigation.MoveController
Starts the NXT robot moving backwards.
backward() - Method in class lejos.robotics.navigation.MovePilot
 
backward() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
backward() - Method in class lejos.robotics.navigation.SteeringPilot
 
backwardStep(int) - Method in class lejos.hardware.device.IRLink
 
backwardStep(int) - Method in interface lejos.hardware.device.IRTransmitter
 
backwardStep(int) - Method in class lejos.hardware.device.RCXLink
 
BAD_ARGUMENTS - Static variable in class lejos.remote.nxt.ErrorMessages
 
BAD_INPUT_OR_OUTPUT_SPECIFIED - Static variable in class lejos.remote.nxt.ErrorMessages
 
Ballbot - Class in lejos.robotics.navigation
This class dynamically stabilizes a ballbot type of robot.
Ballbot(EncoderMotor, Gyroscope, EncoderMotor, Gyroscope, double) - Constructor for class lejos.robotics.navigation.Ballbot
 
base - Variable in class lejos.hardware.lcd.Font
 
BASELINE - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Position the anchor point at the baseline of text.
BaseMotor - Interface in lejos.robotics
Base motor interface.
baseReg - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
BaseRegulatedMotor - Class in lejos.hardware.motor
Abstraction for a Regulated motor motor.
BaseRegulatedMotor(TachoMotorPort, MotorRegulator, int, float, float, float, float, float, float, int, int) - Constructor for class lejos.hardware.motor.BaseRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
BaseRegulatedMotor(Port, MotorRegulator, int, float, float, float, float, float, float, int, int) - Constructor for class lejos.hardware.motor.BaseRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
BaseSensor - Class in lejos.hardware.sensor
 
BaseSensor() - Constructor for class lejos.hardware.sensor.BaseSensor
 
BasicMotor - Class in lejos.hardware.motor
Abstraction for basic motor operations.
BasicMotor() - Constructor for class lejos.hardware.motor.BasicMotor
 
BasicMotorPort - Interface in lejos.hardware.port
An abstraction for a motor port that supports RCX type motors, but not NXT motors with tachometers.
BasicSensorPort - Interface in lejos.hardware.port
An abstraction for a sensor port that supports setting and retrieving types and modes of sensors.
Battery - Class in lejos.hardware
 
Battery() - Constructor for class lejos.hardware.Battery
 
battery - Variable in class lejos.hardware.ev3.LocalEV3
 
BeaconLocator - Interface in lejos.robotics.localization
A class that scans a room for beacons and identifies the angles to the beacons.
BeaconPoseProvider - Class in lejos.robotics.localization
A PoseProvider that uses beacon triangulation to pinpoint the pose (x, y, heading) of a robot.
BeaconPoseProvider(BeaconLocator, BeaconTriangle, MoveProvider) - Constructor for class lejos.robotics.localization.BeaconPoseProvider
Creates a PoseProvider using beacons.
BeaconPoseProvider(BeaconLocator, BeaconTriangle, MoveProvider, int) - Constructor for class lejos.robotics.localization.BeaconPoseProvider
Creates a PoseProvider using beacons.
BeaconTriangle - Class in lejos.robotics.localization
This class represents three beacons in a triangle.
BeaconTriangle(Point, Point, Point) - Constructor for class lejos.robotics.localization.BeaconTriangle
 
beep() - Method in class lejos.hardware.device.IRLink
 
beep() - Method in interface lejos.hardware.device.IRTransmitter
 
BEEP - Static variable in class lejos.hardware.device.RCXLink
NOTE: The BEEP macro is unreliable.
beep() - Method in class lejos.hardware.device.RCXLink
 
beep() - Static method in class lejos.hardware.Sound
Beeps once.
BEEP - Static variable in interface lejos.hardware.Sounds
 
beepSequence() - Static method in class lejos.hardware.Sound
Downward tones.
beepSequenceUp() - Static method in class lejos.hardware.Sound
Upward tones.
Behavior - Interface in lejos.robotics.subsumption
The Behavior interface represents an object embodying a specific behavior belonging to a robot.
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.CommonLCD
Standard two input BitBlt function with the LCD display as the destination.
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.CommonLCD
Standard two input BitBlt function.
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Static method in class lejos.hardware.lcd.LCD
Standard two input BitBlt function with the LCD display as the destination.
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Static method in class lejos.hardware.lcd.LCD
Standard two input BitBlt function.
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
bitBlt(byte[], int, int, int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMITextLCD
 
bitBlt(byte[], int, int, int, int, byte[], int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMITextLCD
 
BLACK - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
BLACK - Static variable in interface lejos.hardware.sensor.SensorConstants
Colors used as the output value when in full mode.
BLACK - Static variable in class lejos.robotics.Color
 
BLANK_INDEX - Static variable in interface lejos.hardware.sensor.SensorConstants
Color sensor data BLANK/Background value index.
block(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
add aNode to list of nodes not a neighbour of this Node
blockTachoCount - Variable in class lejos.remote.nxt.OutputState
 
BLUE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
BLUE - Static variable in class lejos.robotics.Color
 
BLUE_INDEX - Static variable in interface lejos.hardware.sensor.SensorConstants
Color sensor data BLUE value index.
Bluetooth - Class in lejos.hardware
 
Bluetooth() - Constructor for class lejos.hardware.Bluetooth
 
bluetoothAddress - Variable in class lejos.remote.nxt.DeviceInfo
 
BluetoothException - Exception in lejos.hardware
Exception thrown when errors are detected in the Bluetooth classes.
BluetoothException() - Constructor for exception lejos.hardware.BluetoothException
 
BluetoothException(String) - Constructor for exception lejos.hardware.BluetoothException
 
BluetoothException(Throwable) - Constructor for exception lejos.hardware.BluetoothException
 
BluetoothException(String, Throwable) - Constructor for exception lejos.hardware.BluetoothException
 
BOOLEANMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
BOOT - Static variable in class lejos.remote.nxt.LCP
 
boot() - Method in class lejos.remote.nxt.NXTCommand
Put the NXT into SAMBA mode, ready to update the firmware.
BOOT - Static variable in interface lejos.remote.nxt.NXTProtocol
 
BOTTOM - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Position the anchor point of text and images below the text or image.
BRAKE - Static variable in interface lejos.remote.nxt.NXTProtocol
Use run/brake instead of run/float in PWM
Brick - Interface in lejos.hardware
 
BrickFinder - Class in lejos.hardware
 
BrickFinder() - Constructor for class lejos.hardware.BrickFinder
 
BrickInfo - Class in lejos.hardware
 
BrickInfo(String, String, String) - Constructor for class lejos.hardware.BrickInfo
 
BROWN - Static variable in interface lejos.hardware.sensor.SensorConstants
 
BROWN - Static variable in class lejos.robotics.Color
 
BTConnection - Class in lejos.remote.nxt
 
BTConnector - Class in lejos.remote.nxt
 
BTConnector() - Constructor for class lejos.remote.nxt.BTConnector
 
buffer - Variable in class lejos.hardware.device.UART.UARTInputStream
 
buffer - Variable in class lejos.hardware.device.UART.UARTOutputStream
 
buffer - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
Button - Class in lejos.hardware
Abstraction for an NXT button.
BUTTON_POLL_INTERVAL - Static variable in class lejos.utility.TextMenu
buzz() - Static method in class lejos.hardware.Sound
Low buzz
BUZZ - Static variable in interface lejos.hardware.Sounds
 
byteData - Variable in class lejos.remote.ev3.EV3Request
 
byteData2 - Variable in class lejos.remote.ev3.EV3Request
 
bytesAvailable() - Method in class lejos.hardware.device.RCXLink
 

C

C - Variable in class lejos.hardware.device.RCXLink
 
C - Variable in class lejos.hardware.device.RCXMotorMultiplexer
 
C - Static variable in class lejos.hardware.motor.Motor
Motor C.
C - Static variable in interface lejos.hardware.port.MotorPort
MotorPort C.
C2 - Static variable in class lejos.hardware.Sound
 
C2 - Static variable in class lejos.remote.nxt.RemoteNXTAudio
 
calcPose(double, double, double) - Method in class lejos.robotics.localization.BeaconTriangle
Triangulates the pose of a robot given three angles to the three beacons.
calculateG(Node) - Method in class lejos.robotics.pathfinding.GridNode
 
calculateG(Node) - Method in class lejos.robotics.pathfinding.Node
Calculates the distance to a neighbor node.
calculateH(Node) - Method in class lejos.robotics.pathfinding.GridNode
 
calculateH(Node) - Method in class lejos.robotics.pathfinding.Node
Calculates the distance to the goal node.
calculateWeight(RangeReadings, RangeMap, float) - Method in class lejos.robotics.localization.MCLParticle
Calculate the weight for this particle by comparing its readings with the robot's readings
calculateWeights(RangeReadings, RangeMap) - Method in class lejos.robotics.localization.MCLParticleSet
Calculate the weight for each particle
calibrate() - Method in class lejos.hardware.device.LSC
This method check LSC connected with NXTe Currently I am debugging
calibrate(float) - Method in class lejos.hardware.sensor.HiTechnicBarometer
Re-calibrates the sensor.
Calibrate - Interface in lejos.robotics
 
calibrate() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Rotates the robot 360 degrees while calibrating the compass resets compass zero to heading at end of calibration
calibrateAngle() - Method in class lejos.hardware.sensor.HiTechnicAngleSensor
Calibrate the zero position of angle.
calibrateBlack() - Method in class lejos.hardware.sensor.MindsensorsLightSensorArray
 
calibrateBlack() - Method in class lejos.hardware.sensor.MindsensorsLineLeader
 
calibratedValue - Variable in class lejos.remote.nxt.InputValues
Currently unused.
calibrateSteering() - Method in class lejos.robotics.navigation.SteeringPilot
This method calibrates the steering mechanism by turning the wheels all the way to the right and left until they encounter resistance and recording the tachometer values.
calibrateWhite() - Method in class lejos.hardware.sensor.MindsensorsLightSensorArray
 
calibrateWhite() - Method in class lejos.hardware.sensor.MindsensorsLineLeader
 
calibrating - Variable in class lejos.robotics.filter.AbstractCalibrationFilter
 
CalibrationFileException(String) - Constructor for exception lejos.robotics.filter.AbstractCalibrationFilter.CalibrationFileException
 
callListeners() - Method in interface lejos.hardware.ListenerCaller
 
callListeners() - Method in class lejos.remote.ev3.RemoteKey
 
callListeners() - Method in class lejos.remote.ev3.RemoteRequestKey
 
cancel() - Method in class lejos.remote.nxt.BTConnector
 
cancel() - Method in class lejos.remote.nxt.NXTCommConnector
Cancel a connection attempt.
cancel() - Method in class lejos.remote.nxt.SocketConnector
 
cartesianPosition(double, double, double) - Method in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
Specifies the location and orientation of the wheel using a cartesian coordinates
CELL_HEIGHT - Static variable in class lejos.hardware.lcd.LCD
 
CELL_WIDTH - Static variable in class lejos.hardware.lcd.LCD
 
CELSIUSMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
CENTER - Static variable in class lejos.hardware.sensor.SumoEyesSensor
The Constant CENTER (2).
ch - Variable in class lejos.remote.ev3.EV3Request
 
chars - Variable in class lejos.remote.ev3.EV3Request
 
Chassis - Interface in lejos.robotics.chassis
Represents the chassis of a robot.
checkValidity(Pose) - Method in class lejos.robotics.navigation.Waypoint
Check that the given pose satisfies the conditions for this way point
clear() - Method in interface lejos.hardware.lcd.CommonLCD
Clear the display.
clear() - Static method in class lejos.hardware.lcd.LCD
Clear the display.
clear(int, int, int) - Static method in class lejos.hardware.lcd.LCD
Clear a contiguous set of characters
clear(int) - Static method in class lejos.hardware.lcd.LCD
Clear an LCD display row
clear(int, int, int) - Method in interface lejos.hardware.lcd.TextLCD
Clear a contiguous set of characters
clear(int) - Method in interface lejos.hardware.lcd.TextLCD
Clear an LCD display row
clear() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
clear() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
clear() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
clear(int, int, int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
clear(int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
clear() - Method in class lejos.remote.ev3.RemoteTextLCD
 
clear(int, int, int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
clear(int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
clear() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
clear() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
clear() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
clear(int, int, int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
clear(int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
clear() - Method in interface lejos.remote.ev3.RMITextLCD
 
clear(int, int, int) - Method in interface lejos.remote.ev3.RMITextLCD
 
clear(int) - Method in interface lejos.remote.ev3.RMITextLCD
 
clear() - Method in class lejos.utility.DebugMessages
Clear LCD
clearance - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
clearDisplay() - Static method in class lejos.hardware.lcd.LCD
 
clearDisplay() - Method in interface lejos.remote.ev3.RMILCD
 
clearDisplay() - Method in class lejos.remote.ev3.RMIRemoteLCD
 
clearPath() - Method in class lejos.robotics.navigation.Navigator
Clears the current path.
Clock - Interface in lejos.robotics
Interface for real time clock devices
clone() - Method in class lejos.robotics.geometry.Line2D
 
clone() - Method in class lejos.robotics.geometry.Point
returns a clone of itself
clone() - Method in class lejos.robotics.geometry.Point2D
 
clone() - Method in class lejos.robotics.geometry.RectangularShape
 
clone() - Method in class lejos.utility.Matrix
Clone the Matrix object.
close() - Method in class lejos.hardware.Device
Close the sensor.
close() - Method in class lejos.hardware.device.DeviceIdentifier
 
close() - Method in class lejos.hardware.device.MMXRegulatedMotor
 
close() - Method in class lejos.hardware.device.PFMotorPort
 
close() - Method in class lejos.hardware.device.RCXPlexedMotorPort
 
close() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
close() - Method in class lejos.hardware.device.UART
 
close() - Method in class lejos.hardware.gps.SimpleGPS
Method used to close connection.
close() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Close the motor regulator.
close() - Method in interface lejos.hardware.port.IOPort
Close the port, the port can not be used after this call.
close() - Method in interface lejos.hardware.video.Video
Close the webcam, the device will not be available after this call
close() - Method in class lejos.remote.ev3.RemoteAnalogPort
 
close() - Method in class lejos.remote.ev3.RemoteI2CPort
 
close() - Method in class lejos.remote.ev3.RemoteIOPort
 
close() - Method in class lejos.remote.ev3.RemoteMotorPort
 
close() - Method in class lejos.remote.ev3.RemoteRequestAnalogPort
 
close() - Method in class lejos.remote.ev3.RemoteRequestI2CPort
 
close() - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
close() - Method in class lejos.remote.ev3.RemoteRequestMotorPort
 
close() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
close() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
close() - Method in class lejos.remote.ev3.RemoteRequestSampleProvider
 
close() - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
close() - Method in class lejos.remote.ev3.RemoteUARTPort
 
close() - Method in interface lejos.remote.ev3.RMIAnalogPort
 
close() - Method in interface lejos.remote.ev3.RMII2CPort
 
close() - Method in interface lejos.remote.ev3.RMIMotorPort
 
close() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
 
close() - Method in class lejos.remote.ev3.RMIRemoteAnalogPort
 
close() - Method in class lejos.remote.ev3.RMIRemoteI2CPort
 
close() - Method in class lejos.remote.ev3.RMIRemoteMotorPort
 
close() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
close() - Method in class lejos.remote.ev3.RMIRemoteSampleProvider
 
close() - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
close() - Method in interface lejos.remote.ev3.RMISampleProvider
 
close() - Method in interface lejos.remote.ev3.RMIUARTPort
 
close() - Method in class lejos.remote.nxt.BTConnection
 
close() - Method in interface lejos.remote.nxt.Connection
 
CLOSE - Static variable in class lejos.remote.nxt.LCP
 
close() - Method in class lejos.remote.nxt.NXTComm
 
close() - Method in class lejos.remote.nxt.NXTCommand
Deprecated.
call disconnect, then close the underlying NXTComm
close() - Method in interface lejos.remote.nxt.NXTCommRequest
Close the connection
close() - Method in class lejos.remote.nxt.NXTConnection
 
close() - Method in class lejos.remote.nxt.NXTInputStream
the stream is restored to its original state - ready to receive more data.
close() - Method in class lejos.remote.nxt.NXTOutputStream
 
CLOSE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
close() - Method in class lejos.remote.nxt.RemoteNXTIOPort
Close the port, the port can not be used after this call.
close() - Method in class lejos.remote.nxt.SocketConnection
 
close() - Method in class lejos.remote.rcx.PacketHandler
Close this packet handler and all lower layers.
close() - Method in class lejos.remote.rcx.RCXAbstractPort
Closes this RCXPort, stopping the Listener thread.
close() - Method in class lejos.remote.rcx.RCXRemoteMotorPort
 
close() - Method in class lejos.robotics.filter.PublishedSource
 
close() - Method in class lejos.robotics.MirrorMotor
 
close() - Method in interface lejos.robotics.RegulatedMotor
Close the port, the port can not be used after this call.
closeFile(byte) - Method in class lejos.remote.nxt.NXTCommand
Closes an open file.
closeList - Variable in class lejos.hardware.Device
 
CMD_AUTOMATIC - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_COL_AMB - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_COL_BLU - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_COL_COL - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_COL_GRN - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_COL_RED - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_CONNECTED - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_DISCONNECTED - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_FLOAT - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_NONE - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_PIN1 - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_PIN5 - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CMD_SET - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CodeTemplate - Class in lejos.hardware.sensor
Sensor name
Description

The code for this sensor has not been tested.

CodeTemplate(Port) - Constructor for class lejos.hardware.sensor.CodeTemplate
Constructor using a unopened port
CodeTemplate(UARTPort) - Constructor for class lejos.hardware.sensor.CodeTemplate
Constructor using a opened and configured port
COL_AMBIENT - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
COL_CAL - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
COL_COLOR - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
COL_REFLECT - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
COL_REFRAW - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
COL_RESET - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
COL_RGBRAW - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
COLOR - Static variable in class lejos.hardware.device.NXTCam
Used by sortBy() to choose sorting criteria based on color id (ordered 0 to 7).
Color - Class in lejos.robotics
Representation of a color, used by color sensors and color detectors.
Color(int, int, int) - Constructor for class lejos.robotics.Color
 
Color(int, int, int, int) - Constructor for class lejos.robotics.Color
 
ColorAdapter - Class in lejos.robotics
 
ColorAdapter(BaseSensor) - Constructor for class lejos.robotics.ColorAdapter
 
ColorDetector - Interface in lejos.robotics
This interface defines the methods of a generic ColorDetector object.
ColorIdentifier - Interface in lejos.robotics
 
colorMap - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
colorMap - Static variable in class lejos.hardware.sensor.NXTColorSensor
 
COMBO_CH1_A_FORWARD_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH1_A_FORWARD_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH1_A_REVERSE_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH1_A_REVERSE_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH2_A_FORWARD_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH2_A_FORWARD_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH2_A_REVERSE_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH2_A_REVERSE_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH3_A_FORWARD_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH3_A_FORWARD_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH3_A_REVERSE_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH3_A_REVERSE_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH4_A_FORWARD_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH4_A_FORWARD_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH4_A_REVERSE_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
COMBO_CH4_A_REVERSE_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
COMMAND - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
command(byte[], int, byte[]) - Method in class lejos.remote.nxt.LCPResponder
Process the actual command Default action is to call the LCP object to emulate the command
CommonLCD - Interface in lejos.hardware.lcd
 
COMMUNICATION_BUS_ERROR - Static variable in class lejos.remote.nxt.ErrorMessages
 
compass - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
COMPASS_DATA - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
compassMode - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
CompassPilot - Class in lejos.robotics.navigation
Deprecated.
This class will disappear in NXJ version 1.0. Compass should be added to a PoseProvider.
CompassPilot(DirectionFinder, float, float, RegulatedMotor, RegulatedMotor) - Constructor for class lejos.robotics.navigation.CompassPilot
Deprecated.
Allocates a CompasPilot object, and sets the physical parameters of the NXT robot.
CompassPilot(DirectionFinder, float, float, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.CompassPilot
Deprecated.
Allocates a CompasPilot object, and sets the physical parameters of the NXT robot.
CompassPoseProvider - Class in lejos.robotics.localization
Pose Provider using a compass (or other direction finder) to provide location and heading data.
CompassPoseProvider(MoveProvider, DirectionFinder) - Constructor for class lejos.robotics.localization.CompassPoseProvider
 
ConcatenationFilter - Class in lejos.robotics.filter
Simple filter to concatenate two sources
ConcatenationFilter(SampleProvider, SampleProvider) - Constructor for class lejos.robotics.filter.ConcatenationFilter
 
configPort - Variable in class lejos.hardware.device.DeviceIdentifier
 
configurate() - Method in class lejos.hardware.device.SensorMux
This method is necessary to execute to connect sensors on it
ConfigurationPort - Interface in lejos.hardware.port
 
configureWifi(String, String) - Method in interface lejos.remote.ev3.RMIMenu
 
conn - Variable in class lejos.remote.nxt.LCPResponder
 
CONN_DAISYCHAIN - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_ERROR - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_INPUT_DUMB - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_INPUT_UART - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_NONE - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_NXT_COLOR - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_NXT_DUMB - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_NXT_IIC - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_OUTPUT_DUMB - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_OUTPUT_INTELLIGENT - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_OUTPUT_TACHO - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
CONN_UNKNOWN - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
connect(String, int) - Method in class lejos.remote.nxt.BTConnector
 
connect(String, int) - Method in class lejos.remote.nxt.NXTCommConnector
Open a connection to the specified name/address using the given I/O mode
connect(NXTCommConnector) - Method in class lejos.remote.nxt.RemoteNXT
 
connect(String, int) - Method in class lejos.remote.nxt.SocketConnector
 
connect() - Method in class lejos.robotics.filter.PublishedSource
 
connect(Node, Node) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
connect(Node, Node) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Attempts to connect two nodes together by adding them as neighbors.
Connection - Interface in lejos.remote.nxt
 
connector - Variable in class lejos.remote.nxt.LCPResponder
 
constructWithCopy(double[][]) - Static method in class lejos.utility.Matrix
Construct a matrix from a copy of a 2-D array.
cont - Static variable in class lejos.hardware.motor.JavaMotorRegulator
 
contains(double, double) - Method in class lejos.robotics.geometry.Line2D
 
contains(Point2D) - Method in class lejos.robotics.geometry.Line2D
 
contains(double, double, double, double) - Method in class lejos.robotics.geometry.Line2D
 
contains(Rectangle2D) - Method in class lejos.robotics.geometry.Line2D
 
contains(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D
 
contains(double, double) - Method in class lejos.robotics.geometry.Rectangle2D
Test if this Rectangle2D contains a rectangle defined by double coordinates
contains(int, int) - Method in class lejos.robotics.geometry.RectangleInt32
Test if a point given by (x,y) coordinates is within the rectangle
contains(Point) - Method in class lejos.robotics.geometry.RectangleInt32
Test if a point is within the rectangle
contains(RectangleInt32) - Method in class lejos.robotics.geometry.RectangleInt32
Test if this rectangle contains a specified rectangle
contains(Point2D) - Method in class lejos.robotics.geometry.RectangularShape
Test if the shape contains a Point2D
contains(Rectangle2D) - Method in class lejos.robotics.geometry.RectangularShape
Test if this shape contains a given Rectangle2D
contains(double, double) - Method in interface lejos.robotics.geometry.Shape
Test if the shape contains the point (x,y)
contains(Point2D) - Method in interface lejos.robotics.geometry.Shape
Test if the shape contains the Point2D
contains(double, double, double, double) - Method in interface lejos.robotics.geometry.Shape
Test if the shape contains the rectangle with top left at (x,y), width w and height h.
contains(Rectangle2D) - Method in interface lejos.robotics.geometry.Shape
Test if the shape contains the Rectangle2D
contents - Variable in class lejos.remote.ev3.EV3Reply
 
contents - Variable in class lejos.remote.ev3.MenuReply
 
contents - Variable in class lejos.remote.ev3.MenuRequest
 
Controller() - Constructor for class lejos.hardware.motor.JavaMotorRegulator.Controller
 
controlMotor(int, int) - Method in class lejos.hardware.device.PFMotorPort
 
controlMotor(int, int) - Method in class lejos.hardware.device.RCXPlexedMotorPort
 
controlMotor(int, int) - Method in interface lejos.hardware.port.BasicMotorPort
 
controlMotor(int, int) - Method in class lejos.remote.ev3.RemoteMotorPort
Low-level method to control a motor.
controlMotor(int, int) - Method in class lejos.remote.ev3.RemoteRequestMotorPort
 
controlMotor(int, int) - Method in interface lejos.remote.ev3.RMIMotorPort
Low-level method to control a motor.
controlMotor(int, int) - Method in class lejos.remote.ev3.RMIRemoteMotorPort
 
controlMotor(int, int) - Method in class lejos.remote.nxt.RemoteNXTMotorPort
Low-level method to control a motor.
controlMotor(int, int) - Method in class lejos.remote.rcx.RCXRemoteMotorPort
 
convert(double, int) - Static method in class lejos.hardware.gps.Coordinates
UNTESTED as of April 7, 2009 - BB / /** Converts a double representation of a coordinate with decimal degrees into a string representation.
convert(String) - Static method in class lejos.hardware.gps.Coordinates
Converts a String representation of a coordinate into the double representation as used in this API.
convert - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
convertAngleToDistance(float, float) - Static method in class lejos.robotics.navigation.Move
Static utility method for converting angle (given turn radius) into distance.
convertDistanceToAngle(float, float) - Static method in class lejos.robotics.navigation.Move
Static utility method for converting distance (given turn radius) into angle.
Coordinates - Class in lejos.hardware.gps
This class has been designed to manage coordinates using JSR-179 Location API http://www.jcp.org/en/jsr/detail?id=179
Coordinates(double, double, double) - Constructor for class lejos.hardware.gps.Coordinates
Create a Coordinate object with 3 parameters: latitude, longitude and altitude
Coordinates(double, double) - Constructor for class lejos.hardware.gps.Coordinates
 
copy() - Method in class lejos.utility.Matrix
Make a deep copy of a matrix
copyAbsolute(Matrix) - Method in class lejos.robotics.chassis.WheeledChassis
Make a copy of the source matrix, each of its element being the absolute value of the elements of the source matrix
copyArea(int, int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Copy one rectangular area of the drawing surface to another.
copyArea(int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
copyArea(int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
copyArea(int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
copyArea(int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
copyTo(Point) - Method in class lejos.robotics.geometry.Point
 
count - Variable in class lejos.hardware.sensor.RCXRotationSensor
 
createAccelerometer(I2CPort) - Static method in class lejos.utility.SensorSelector
 
createFrame() - Method in interface lejos.hardware.video.Video
Create a byte array suitable for holding a single video frame
createImage(int, int) - Static method in class lejos.hardware.lcd.Image
Create ablank image of the requested size.
createImage(InputStream) - Static method in class lejos.hardware.lcd.Image
Read image from file.
createImage(Image, int, int, int, int, int) - Static method in class lejos.hardware.lcd.Image
Creates a new image based upon the transformed region of another image
createIRTransmitter(I2CPort) - Static method in class lejos.utility.SensorSelector
 
createPilot(double, double, String, String) - Method in class lejos.remote.ev3.RemoteRequestEV3
 
createRegulatedMotor(String, char) - Method in class lejos.remote.ev3.RemoteEV3
 
createRegulatedMotor(String, char) - Method in class lejos.remote.ev3.RemoteRequestEV3
 
createRegulatedMotor(String, char) - Method in interface lejos.remote.ev3.RMIEV3
 
createRegulatedMotor(String, char) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
createSampleProvider(String, String, String) - Method in class lejos.remote.ev3.RemoteEV3
 
createSampleProvider(String, String, String) - Method in class lejos.remote.ev3.RemoteRequestEV3
 
createSampleProvider(String, String, String, String, float) - Method in class lejos.remote.ev3.RemoteRequestEV3
 
createSampleProvider(String, String, String) - Method in interface lejos.remote.ev3.RMIEV3
 
createSampleProvider(String, String, String) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
createSVGFile(String) - Method in class lejos.robotics.mapping.LineMap
Create an SVG map file
CruizcoreGyro - Class in lejos.hardware.sensor
Micro Infinity Cruizcore XG1300L
The XG1300L is a fully self-contained digital MEMS gyroscope and accelerometer.
CruizcoreGyro(I2CPort) - Constructor for class lejos.hardware.sensor.CruizcoreGyro
Instantiates a new Cruizcore Gyro sensor.
CruizcoreGyro(Port) - Constructor for class lejos.hardware.sensor.CruizcoreGyro
 
cs - Static variable in class lejos.remote.nxt.NXTCommDevice
 
currentMode - Variable in class lejos.hardware.sensor.BaseSensor
 
currentMode - Variable in class lejos.hardware.sensor.UARTSensor
 
currentMode - Variable in class lejos.remote.ev3.RemoteIOPort
 
currentMode - Variable in class lejos.remote.ev3.RemoteRequestIOPort
 
currentMode - Variable in class lejos.remote.nxt.RemoteNXTIOPort
 
currentPose - Variable in class lejos.robotics.mapping.NavigationModel
 
currentType - Variable in class lejos.hardware.sensor.AnalogSensor
 
CUSTOM - Static variable in interface lejos.remote.nxt.NXTProtocol
 
CYAN - Static variable in class lejos.robotics.Color
 

D

D - Variable in class lejos.hardware.device.RCXMotorMultiplexer
 
D - Static variable in class lejos.hardware.motor.Motor
Motor D.
D - Static variable in interface lejos.hardware.port.MotorPort
MotorPort D.
DAISY_CHAIN_POSITION_1 - Static variable in class lejos.hardware.device.tetrix.TetrixControllerFactory
Position 1 (nearest to the NXT) in the daisy chain.
DAISY_CHAIN_POSITION_2 - Static variable in class lejos.hardware.device.tetrix.TetrixControllerFactory
Position 2 in the daisy chain.
DAISY_CHAIN_POSITION_3 - Static variable in class lejos.hardware.device.tetrix.TetrixControllerFactory
Position 3 in the daisy chain.
DAISY_CHAIN_POSITION_4 - Static variable in class lejos.hardware.device.tetrix.TetrixControllerFactory
Position 3 (furthest from the NXT)in the daisy chain.
DARK_GRAY - Static variable in class lejos.robotics.Color
 
DATA_10BIT_REG - Static variable in class lejos.hardware.sensor.DexterIMUSensor.DexterIMUAccelerationSensor
 
DATA_8BIT_REG - Static variable in class lejos.hardware.sensor.DexterIMUSensor.DexterIMUAccelerationSensor
 
DATA_CONTAINS_OUT_OF_RANGE_VALUES - Static variable in class lejos.remote.nxt.ErrorMessages
 
datagramSocket - Variable in class lejos.robotics.filter.PublishFilter
 
DBMode() - Constructor for class lejos.hardware.sensor.NXTSoundSensor.DBMode
 
dc - Static variable in class lejos.remote.nxt.RemoteNXTIOPort
 
DCMotor - Interface in lejos.robotics
Interface for a regular DC motor.
DD_MM - Static variable in class lejos.hardware.gps.Coordinates
Identifier for string coordinate representation Degrees, Minutes, decimal fractions of a minute See Also:Constant Field Values
DD_MM_SS - Static variable in class lejos.hardware.gps.Coordinates
Identifier for string coordinate representation Degrees, Minutes, Seconds and decimal fractions of a second See Also:Constant Field Values
debug - Variable in class lejos.robotics.mapping.NavigationModel
 
DebugMessages - Class in lejos.utility
This class has been developed to use it in case of you have to tests leJOS programs and you need to show in NXT Display data but you don't need to design a User Interface.
DebugMessages() - Constructor for class lejos.utility.DebugMessages
 
DebugMessages(int) - Constructor for class lejos.utility.DebugMessages
Constructor which the user establish in what line start showing messages
debugProgram(String) - Method in interface lejos.remote.ev3.Menu
 
debugProgram(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
debugProgram(String) - Method in interface lejos.remote.ev3.RMIMenu
 
decode(byte[]) - Static method in class lejos.remote.nxt.AsciizCodec
Convert an ASCIIZ byte array to a string
decodeIntBE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeIntLE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeLongBE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeLongLE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeShortBE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeShortLE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeUIntBE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeUIntLE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeUShortBE(byte[], int) - Static method in class lejos.utility.EndianTools
 
decodeUShortLE(byte[], int) - Static method in class lejos.utility.EndianTools
 
DEFAULT_I2C_ADDRESS - Static variable in class lejos.hardware.sensor.I2CSensor
 
DEFAULT_I2C_ADDRESS - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
The default I2C address of the sensor
DEFAULT_MMX_ADDRESS - Static variable in class lejos.hardware.device.NXTMMX
The default I2C address (0x06) for the NXTMMX.
DEFAULT_PFMATE_ADDRESS - Static variable in class lejos.hardware.device.PFMate
 
DEFAULT_RCXMMUX_ADDRESS - Static variable in class lejos.hardware.device.RCXMotorMultiplexer
 
DEFAULT_RCXSMUX_ADDRESS - Static variable in class lejos.hardware.device.RCXSensorMultiplexer
 
defineAndRun(byte[], int) - Method in class lejos.hardware.device.RCXLink
 
defineMacro(int, byte[]) - Method in class lejos.hardware.device.RCXLink
 
defrag() - Method in class lejos.remote.nxt.NXTCommand
A NXJ extension to defrag the file system
degreesMinToDegrees(String, int) - Method in class lejos.hardware.gps.NMEASentence
Any GPS Receiver gives Lat/Lon data in the following way: http://www.gpsinformation.org/dale/nmea.htm http://www.teletype.com/pages/support/Documentation/RMC_log_info.htm 4807.038,N Latitude 48 deg 07.038' N 01131.000,E Longitude 11 deg 31.000' E This data is necessary to convert to Decimal Degrees.
degreesMinToDegreesDbl(String, int) - Method in class lejos.hardware.gps.GGASentence
Any GPS Receiver gives Lat/Lon data in the following way: http://www.gpsinformation.org/dale/nmea.htm http://www.teletype.com/pages/support/Documentation/RMC_log_info.htm 4807.038,N Latitude 48 deg 07.038' N 01131.000,E Longitude 11 deg 31.000' E This data is necessary to convert to Decimal Degrees.
degreesMinToDegreesDbl(String, int) - Method in class lejos.hardware.gps.RMCSentence
Any GPS Receiver gives Lat/Lon data in the following way: http://www.gpsinformation.org/dale/nmea.htm http://www.teletype.com/pages/support/Documentation/RMC_log_info.htm 4807.038,N Latitude 48 deg 07.038' N 01131.000,E Longitude 11 deg 31.000' E This data is necessary to convert to Decimal Degrees.
DELAY - Static variable in class lejos.hardware.device.RCXLink
 
Delay - Class in lejos.utility
Simple collection of time delay routines that are non interruptable.
Delay() - Constructor for class lejos.utility.Delay
 
DELETE - Static variable in class lejos.remote.nxt.LCP
 
delete(String) - Method in class lejos.remote.nxt.NXTCommand
Delete a file on the NXT
DELETE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
DELETE_USER_FLASH - Static variable in class lejos.remote.nxt.LCP
 
DELETE_USER_FLASH - Static variable in interface lejos.remote.nxt.NXTProtocol
 
deleteAllPrograms() - Method in interface lejos.remote.ev3.Menu
 
deleteAllPrograms() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
deleteAllPrograms() - Method in interface lejos.remote.ev3.RMIMenu
 
deleteFile(String) - Method in interface lejos.remote.ev3.Menu
 
deleteFile(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
deleteFile(String) - Method in interface lejos.remote.ev3.RMIMenu
 
deleteUserFlash() - Method in class lejos.remote.nxt.NXTCommand
Deletes user flash memory.
DESCENDING - Static variable in interface lejos.hardware.Sounds
 
DestinationUnreachableException - Exception in lejos.robotics.navigation
Exception thrown by path finders when the destination cannot be reached
DestinationUnreachableException() - Constructor for exception lejos.robotics.navigation.DestinationUnreachableException
 
det() - Method in class lejos.utility.LUDecomposition
Determinant
detectors - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
Device - Class in lejos.hardware
Base class for sensor drivers.
Device() - Constructor for class lejos.hardware.Device
 
DeviceException - Exception in lejos.hardware
Exception thrown when errors are detected in a sensor device state.
DeviceException() - Constructor for exception lejos.hardware.DeviceException
 
DeviceException(String) - Constructor for exception lejos.hardware.DeviceException
 
DeviceException(Throwable) - Constructor for exception lejos.hardware.DeviceException
 
DeviceException(String, Throwable) - Constructor for exception lejos.hardware.DeviceException
 
DeviceIdentifier - Class in lejos.hardware.device
 
DeviceIdentifier(Port) - Constructor for class lejos.hardware.device.DeviceIdentifier
Create an instance of the device identifier for a particular port
DeviceInfo - Class in lejos.remote.nxt
Represents a remote NXT accessed via LCP.
DeviceInfo() - Constructor for class lejos.remote.nxt.DeviceInfo
 
DexterCompassSensor - Class in lejos.hardware.sensor
Dexter Industries dCompass sensor
A three axis magnetometer
DexterCompassSensor(I2CPort) - Constructor for class lejos.hardware.sensor.DexterCompassSensor
Constructor for the driver.
DexterCompassSensor(Port) - Constructor for class lejos.hardware.sensor.DexterCompassSensor
 
DexterGPSSensor - Class in lejos.hardware.sensor
Dexter dGPS sensor
Sends GPS coordinates to your robot and calculates navigation information

The code for this sensor has not been tested.

DexterGPSSensor(I2CPort) - Constructor for class lejos.hardware.sensor.DexterGPSSensor
Constructor
DexterGPSSensor(Port) - Constructor for class lejos.hardware.sensor.DexterGPSSensor
Constructor
DexterIMUSensor - Class in lejos.hardware.sensor
Dexter Industries dIMU Sensor
An accelerometer and gyroscope for the LEGO® MINDSTORMS® NXT and EV3.
DexterIMUSensor(I2CPort) - Constructor for class lejos.hardware.sensor.DexterIMUSensor
 
DexterIMUSensor(Port) - Constructor for class lejos.hardware.sensor.DexterIMUSensor
 
DexterIMUSensor.DexterIMUAccelerationSensor - Class in lejos.hardware.sensor
Class to access the Acceleration sensor from Dexter Industries IMU the acceleration sensor is the Freescale MMA7455
DexterLaserSensor - Class in lejos.hardware.sensor
Dexter laser sensor
The sensor contains a laser and a photodiode to read ambient light values.
The Dexter Industries laser can turn on and off very rapidly, with the following characteristics:
DexterLaserSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.DexterLaserSensor
Create a laser sensor object attached to the specified port, and sets the laser on or off.
DexterLaserSensor(Port) - Constructor for class lejos.hardware.sensor.DexterLaserSensor
Create a laser sensor object attached to the specified port, and sets the laser on or off.
DexterPressureSensor250 - Class in lejos.hardware.sensor
Dexter Industries DPressure250
Pressure sensor for LEGO® MINDSTORMS® EV3 and NXT.
DexterPressureSensor250(AnalogPort) - Constructor for class lejos.hardware.sensor.DexterPressureSensor250
 
DexterPressureSensor250(Port) - Constructor for class lejos.hardware.sensor.DexterPressureSensor250
 
DexterPressureSensor500 - Class in lejos.hardware.sensor
Dexter Industries DPressure500
Pressure sensor for LEGO® MINDSTORMS® EV3 and NXT.
DexterPressureSensor500(AnalogPort) - Constructor for class lejos.hardware.sensor.DexterPressureSensor500
 
DexterPressureSensor500(Port) - Constructor for class lejos.hardware.sensor.DexterPressureSensor500
 
DexterThermalIRSensor - Class in lejos.hardware.sensor
Dexter Industries Thermal Infrared Sensor
The Dexter Industries Thermal Infrared Sensor reads surface temperatures of objects.
DexterThermalIRSensor(I2CPort) - Constructor for class lejos.hardware.sensor.DexterThermalIRSensor
Construct a sensor instance that is connected to port.
DexterThermalIRSensor(Port) - Constructor for class lejos.hardware.sensor.DexterThermalIRSensor
 
DGPS_CMD_ANGD - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_ANGR - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_DIST - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_HEAD - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_LAT - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_LONG - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_SLAT - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_SLONG - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_STATUS - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_UTC - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_CMD_VELO - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
DGPS_I2C_ADDR - Static variable in class lejos.hardware.sensor.DexterGPSSensor
 
diameter - Variable in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
diameter - Variable in class lejos.robotics.chassis.WheeledChassis.Modeler
 
DifferentialPilot - Class in lejos.robotics.navigation
Deprecated.
use MovePilot instead.
DifferentialPilot(double, double, RegulatedMotor, RegulatedMotor) - Constructor for class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
Assumes Motor.forward() causes the robot to move forward.
DifferentialPilot(double, double, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
DifferentialPilot(double, double, double, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
DijkstraPathFinder - Class in lejos.robotics.pathfinding
This class calculates the shortest path from a starting point to a finish point.
DijkstraPathFinder(LineMap) - Constructor for class lejos.robotics.pathfinding.DijkstraPathFinder
 
DijkstraPathFinder.Node - Class in lejos.robotics.pathfinding
 
DIRECT_COMMAND_NOREPLY - Static variable in class lejos.remote.nxt.LCP
 
DIRECT_COMMAND_NOREPLY - Static variable in interface lejos.remote.nxt.NXTProtocol
 
DIRECT_COMMAND_REPLY - Static variable in class lejos.remote.nxt.LCP
 
DIRECT_COMMAND_REPLY - Static variable in interface lejos.remote.nxt.NXTProtocol
 
DirectionFinder - Interface in lejos.robotics
Abstraction for compasses and other devices than return the heading of a robot.
DirectionFinderAdapter - Class in lejos.robotics
 
DirectionFinderAdapter(SampleProvider) - Constructor for class lejos.robotics.DirectionFinderAdapter
 
DIRECTORY_FULL - Static variable in class lejos.remote.nxt.ErrorMessages
 
dis - Variable in class lejos.robotics.filter.PublishedSource
 
dis - Variable in class lejos.robotics.mapping.NavigationModel
 
disable() - Method in interface lejos.hardware.device.DLight
Disables the dLight.
disable(int) - Method in class lejos.hardware.device.DLights
Disables the dLight.
disable() - Method in class lejos.hardware.sensor.EV3UltrasonicSensor
Disable the sensor.
disable() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
 
disableBlinking() - Method in interface lejos.hardware.device.DLight
Disables blinking.
disableBlinking(int) - Method in class lejos.hardware.device.DLights
Disables blinking.
discardEvents() - Static method in class lejos.hardware.Button
This method discards any events.
discardEvents() - Method in class lejos.hardware.device.MindSensorsNumPad
This method discards any events.
discardEvents() - Method in interface lejos.hardware.Keys
 
discardEvents() - Method in class lejos.remote.ev3.RemoteKeys
 
discardEvents() - Method in class lejos.remote.ev3.RemoteRequestKeys
 
discardEvents() - Method in interface lejos.remote.ev3.RMIKeys
 
discardEvents() - Method in class lejos.remote.ev3.RMIRemoteKeys
 
disconnect() - Method in class lejos.hardware.LocalBTDevice
 
disConnect() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
disConnect() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
disconnect() - Method in class lejos.remote.nxt.LCPResponder
Method called to disconnect the responder connect.
disconnect() - Method in class lejos.remote.nxt.NXTCommand
Tell the NXT that the connection is aborted.
disconnect(Node, Node) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
disconnect(Node, Node) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Disconnects two nodes by removing them as neighbors.
discover() - Static method in class lejos.hardware.BrickFinder
Search for available EV3s and populate table with results.
discoverNXT() - Static method in class lejos.hardware.BrickFinder
 
display(GraphicsLCD, int, int, int) - Method in class lejos.hardware.video.YUYVImage
Display the image at the specified location on the provided monochrome device or image.
display(int, int) - Method in class lejos.utility.TextMenu
helper method used by select()
DISPLAY_CHAR_DEPTH - Static variable in class lejos.hardware.lcd.LCD
 
DISPLAY_CHAR_WIDTH - Static variable in class lejos.hardware.lcd.LCD
 
distance(Coordinates) - Method in class lejos.hardware.gps.Coordinates
Calculates the geodetic distance between the two points according to the ellipsoid model of WGS84.
distance(double, double, double, double) - Static method in class lejos.robotics.geometry.Point2D
Get the the distance between two points
distance(double, double) - Method in class lejos.robotics.geometry.Point2D
Get the distance from this point to a given point as a double
distance(Point2D) - Method in class lejos.robotics.geometry.Point2D
Get the distance from this point to a given point asa double
DistanceMode() - Constructor for class lejos.hardware.sensor.NXTUltrasonicSensor.DistanceMode
 
distanceSq(double, double, double, double) - Static method in class lejos.robotics.geometry.Point2D
Get the square of the distance between two points
distanceSq(double, double) - Method in class lejos.robotics.geometry.Point2D
Get the square of the distance between two points
distanceSq(Point2D) - Method in class lejos.robotics.geometry.Point2D
Get the square of the distance of this point to a given point
distanceTo(Point) - Method in class lejos.robotics.navigation.Pose
Return the distance to the destination
distBetweenPoints(Point, Point) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Calculates the distance between any two points.
DLight - Interface in lejos.hardware.device
Interface for dLights from Dexter Industries
DLights - Class in lejos.hardware.device
The DLights class drives up to four dLights on a single sensor port.
DLights(I2CPort) - Constructor for class lejos.hardware.device.DLights
Constructor for DLights.
DLights(Port) - Constructor for class lejos.hardware.device.DLights
 
dos - Variable in class lejos.robotics.mapping.NavigationModel
 
dotProduct(Point) - Method in class lejos.robotics.geometry.Point
Returns the inner dot product.
DOTTED - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Constant for the DOTTED stroke style.
Double() - Constructor for class lejos.robotics.geometry.Line2D.Double
Create a zero length line at (0,0) with double coordinates
Double(double, double, double, double) - Constructor for class lejos.robotics.geometry.Line2D.Double
Create a line from (x1,y1) to (x2,y2) with double coordinate
Double() - Constructor for class lejos.robotics.geometry.Point2D.Double
Create a point at (0,0) with double coordinates
Double(double, double) - Constructor for class lejos.robotics.geometry.Point2D.Double
Create a point at (x,y) with double coordinates
Double() - Constructor for class lejos.robotics.geometry.Rectangle2D.Double
Create an empty rectangle at (0,0)
Double(double, double, double, double) - Constructor for class lejos.robotics.geometry.Rectangle2D.Double
 
DOUBLE_BEEP - Static variable in interface lejos.hardware.Sounds
 
doubleReply - Variable in class lejos.remote.ev3.EV3Reply
 
doubleValue - Variable in class lejos.remote.ev3.EV3Request
 
doubleValue2 - Variable in class lejos.remote.ev3.EV3Request
 
DOWN - Static variable in class lejos.hardware.Button
The Down button.
down - Variable in class lejos.hardware.ev3.LocalEV3
 
DOWN - Static variable in interface lejos.hardware.Key
 
DOWN - Static variable in interface lejos.remote.ev3.RMIKey
 
drawArc(int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw an arc, using the current color and style.
drawArc(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawArc(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawArc(int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawArc(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawChar(char, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a single character to the graphics surface using the current color.
drawChar(char, int, int) - Static method in class lejos.hardware.lcd.LCD
Draw a single char on the LCD at specified x,y co-ordinate.
drawChar(char, int, int) - Method in interface lejos.hardware.lcd.TextLCD
Draw a single char on the LCD at specified x,y co-ordinate.
drawChar(char, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawChar(char, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawChar(char, int, int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
drawChar(char, int, int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
drawChar(char, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawChar(char, int, int) - Method in interface lejos.remote.ev3.RMILCD
 
drawChar(char, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawChar(char, int, int) - Method in class lejos.remote.ev3.RMIRemoteLCD
 
drawChar(char, int, int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
drawChar(char, int, int) - Method in interface lejos.remote.ev3.RMITextLCD
 
drawChars(char[], int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a series of characters to the graphics surface using the current color.
drawChars(char[], int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawChars(char[], int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawChars(char[], int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawChars(char[], int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawImage(Image, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw the specified image to the graphics surface, using the supplied rop.
drawImage(Image, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawImage(Image, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawImage(Image, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawImage(Image, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawInt(int, int, int) - Static method in class lejos.hardware.lcd.LCD
Display an int on the LCD at specified x,y co-ordinate.
drawInt(int, int, int, int) - Static method in class lejos.hardware.lcd.LCD
Display an in on the LCD at x,y with leading spaces to occupy at least the number of characters specified by the places parameter.
drawInt(int, int, int) - Method in interface lejos.hardware.lcd.TextLCD
Display an int on the LCD at specified x,y co-ordinate.
drawInt(int, int, int, int) - Method in interface lejos.hardware.lcd.TextLCD
Display an in on the LCD at x,y with leading spaces to occupy at least the number of characters specified by the places parameter.
drawInt(int, int, int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
drawInt(int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
drawInt(int, int, int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
drawInt(int, int, int, int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
drawInt(int, int, int) - Method in interface lejos.remote.ev3.RMILCD
 
drawInt(int, int, int, int) - Method in interface lejos.remote.ev3.RMILCD
 
drawInt(int, int, int) - Method in class lejos.remote.ev3.RMIRemoteLCD
 
drawInt(int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteLCD
 
drawInt(int, int, int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
drawInt(int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
drawInt(int, int, int) - Method in interface lejos.remote.ev3.RMITextLCD
 
drawInt(int, int, int, int) - Method in interface lejos.remote.ev3.RMITextLCD
 
drawLine(int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a line between the specified points, using the current color and style.
drawLine(int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawLine(int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawLine(int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawLine(int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawRect(int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a rectangle using the current color and style.
drawRect(int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawRect(int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawRect(int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawRect(int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawRegion(Image, int, int, int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw the specified region of the supplied image to the graphics surface.
drawRegion(Image, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawRegion(Image, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawRegion(Image, int, int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawRegion(Image, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw the specified image to the graphics surface, using the supplied rop.
drawRegionRop(Image, int, int, int, int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw the specified region of the source image to the graphics surface after applying the requested transformation, use the supplied rop.
drawRegionRop(Image, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawRegionRop(Image, int, int, int, int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawRoundRect(int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a rounded rectangle.
drawRoundRect(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawRoundRect(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawRoundRect(int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawRoundRect(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawString(String, int, int, int, boolean) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draws the specified String using the current font and color.
drawString(String, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draws the specified String using the current font and color.
drawString(String, int, int, boolean) - Static method in class lejos.hardware.lcd.LCD
Display an optionally inverted string on the LCD at specified x,y co-ordinate.
drawString(String, int, int) - Static method in class lejos.hardware.lcd.LCD
Display a string on the LCD at specified x,y co-ordinate.
drawString(String, int, int, boolean) - Method in interface lejos.hardware.lcd.TextLCD
Display an optionally inverted string on the LCD at specified x,y co-ordinate.
drawString(String, int, int) - Method in interface lejos.hardware.lcd.TextLCD
Display a string on the LCD at specified x,y co-ordinate.
drawString(String, int, int, int, boolean) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawString(String, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawString(String, int, int, int, boolean) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawString(String, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawString(String, int, int, boolean) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
drawString(String, int, int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
drawString(String, int, int, boolean) - Method in class lejos.remote.ev3.RemoteTextLCD
 
drawString(String, int, int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
drawString(String, int, int, int, boolean) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawString(String, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawString(String, int, int, boolean) - Method in interface lejos.remote.ev3.RMILCD
 
drawString(String, int, int) - Method in interface lejos.remote.ev3.RMILCD
 
drawString(String, int, int, int, boolean) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawString(String, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
drawString(String, int, int, boolean) - Method in class lejos.remote.ev3.RMIRemoteLCD
 
drawString(String, int, int) - Method in class lejos.remote.ev3.RMIRemoteLCD
 
drawString(String, int, int, boolean) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
drawString(String, int, int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
drawString(String, int, int, boolean) - Method in interface lejos.remote.ev3.RMITextLCD
 
drawString(String, int, int) - Method in interface lejos.remote.ev3.RMITextLCD
 
drawSubstring(String, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a substring to the graphics surface using the current color.
drawSubstring(String, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
drawSubstring(String, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
drawSubstring(String, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
drawSubstring(String, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
dummyWheels - Variable in class lejos.robotics.chassis.WheeledChassis
The program adds a dummy wheel to a differential chassis.
Dump - Class in lejos.robotics.filter
 
Dump(SampleProvider) - Constructor for class lejos.robotics.filter.Dump
 
Dump(SampleProvider, String) - Constructor for class lejos.robotics.filter.Dump
 
dumpClosest(RangeReadings, DataOutputStream, float, float) - Method in class lejos.robotics.localization.MCLParticleSet
Find the closest particle to specified coordinates and dump its details to a data output stream.
dumpObject(DataOutputStream) - Method in class lejos.robotics.localization.MCLParticleSet
Serialize the particle set to a data output stream
dumpObject(DataOutputStream) - Method in class lejos.robotics.localization.MCLPoseProvider
Dump the serialized estimate of pose to a data output stream
dumpObject(DataOutputStream) - Method in class lejos.robotics.mapping.LineMap
Dump the map to a DataOutputStream
dumpObject(DataOutputStream) - Method in class lejos.robotics.navigation.Move
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.navigation.Pose
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.navigation.Waypoint
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.objectdetection.RangeFeature
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.pathfinding.Path
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.RangeReadings
Dump the readings to a DataOutputStream
dumpObject(DataOutputStream) - Method in interface lejos.robotics.Transmittable
 

E

e - Variable in class lejos.remote.ev3.EV3Reply
 
echo(String) - Method in class lejos.utility.DebugMessages
Show in NXT Screen a message
echo(int) - Method in class lejos.utility.DebugMessages
Show in NXT Screen a message
EEPROM_BUFFER - Static variable in class lejos.hardware.device.RCXLink
 
elapsed() - Method in class lejos.utility.Stopwatch
Return elapsed time in milliseconds
emulateCommand(byte[], int, byte[]) - Static method in class lejos.remote.nxt.LCP
Emulates a Lego firmware Direct or System command
enable() - Method in interface lejos.hardware.device.DLight
Enables the dLight.
enable(int) - Method in class lejos.hardware.device.DLights
Enables the dLight.
enable() - Method in class lejos.hardware.sensor.EV3UltrasonicSensor
Enable the sensor.
enable() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
 
enableBlinking() - Method in interface lejos.hardware.device.DLight
Enables blinking pattern.
enableBlinking(int) - Method in class lejos.hardware.device.DLights
Enables blinking pattern.
enableDetection(boolean) - Method in interface lejos.robotics.objectdetection.FeatureDetector
Enable or disable detection of objects.
enableDetection(boolean) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
enableDetection(boolean) - Method in class lejos.robotics.objectdetection.FusorDetector
This method enables/disables automatic scanning and listener reporting for this object and all FeatureDetectors used in this FusorDetector object.
enableTracking(boolean) - Method in class lejos.hardware.device.NXTCam
 
encode(String) - Static method in class lejos.remote.nxt.AsciizCodec
Encode a string as ASCIIZ
encodeIntBE(int, byte[], int) - Static method in class lejos.utility.EndianTools
 
encodeIntLE(int, byte[], int) - Static method in class lejos.utility.EndianTools
 
encodeLongBE(long, byte[], int) - Static method in class lejos.utility.EndianTools
 
encodeLongLE(long, byte[], int) - Static method in class lejos.utility.EndianTools
 
Encoder - Interface in lejos.robotics
Abstraction for the tachometer built into NXT motors.
EncoderMotor - Interface in lejos.robotics
An EncoderMotor is a platform independent interface for an unregulated motor that also has basic tachometer functions.
encoderPort - Variable in class lejos.hardware.motor.UnregulatedMotor
 
encodeShortBE(int, byte[], int) - Static method in class lejos.utility.EndianTools
 
encodeShortLE(int, byte[], int) - Static method in class lejos.utility.EndianTools
 
END_CALIBRATION - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
END_OF_FILE - Static variable in class lejos.remote.nxt.ErrorMessages
 
END_OF_FILE_EXPECTED - Static variable in class lejos.remote.nxt.ErrorMessages
 
EndianTools - Class in lejos.utility
Tools for manipulating numbers in little-endian and big-endian encodings
EndianTools() - Constructor for class lejos.utility.EndianTools
 
endSynchronization() - Method in class lejos.hardware.device.MMXRegulatedMotor
 
endSynchronization() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
endSynchronization() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Complete a set of synchronized motor operations.
endSynchronization(boolean) - Method in class lejos.hardware.motor.JavaMotorRegulator
 
endSynchronization(boolean) - Method in interface lejos.hardware.motor.MotorRegulator
Complete a set of synchronized motor operations.
endSynchronization() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
endSynchronization() - Method in class lejos.robotics.MirrorMotor
 
endSynchronization() - Method in interface lejos.robotics.RegulatedMotor
Complete a set of synchronized motor operations.
ENTER - Static variable in class lejos.hardware.Button
The Enter button.
enter - Variable in class lejos.hardware.ev3.LocalEV3
 
ENTER - Static variable in interface lejos.hardware.Key
 
ENTER - Static variable in interface lejos.remote.ev3.RMIKey
 
equals(Object) - Method in class lejos.robotics.geometry.Point2D
Test if this point is equal to a given object
equals(Object) - Method in class lejos.robotics.geometry.Rectangle2D
Test if the rectangle is equal to a given object
equals(Object) - Method in class lejos.robotics.geometry.RectangleInt32
Test if the Rectangle is equal to a given object
equals(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
ERROR - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
error(String) - Method in class lejos.robotics.mapping.EV3NavigationModel
Display an error message to the user
ErrorMessages - Class in lejos.remote.nxt
Error messages that can be returned after a call to the NXT brick.
ESCAPE - Static variable in class lejos.hardware.Button
The Escape button.
escape - Variable in class lejos.hardware.ev3.LocalEV3
 
ESCAPE - Static variable in interface lejos.hardware.Key
 
ESCAPE - Static variable in interface lejos.remote.ev3.RMIKey
 
estimatePose() - Method in class lejos.robotics.localization.MCLPoseProvider
Estimate pose from weighted average of the particles Calculate statistics
EV3 - Interface in lejos.hardware.ev3
 
ev3 - Static variable in class lejos.hardware.ev3.LocalEV3
 
EV3AnalogMap - Static variable in class lejos.hardware.device.DeviceIdentifier
 
EV3ColorSensor - Class in lejos.hardware.sensor
EV3 color sensor
The digital EV3 Color Sensor distinguishes between eight different colors.
EV3ColorSensor(UARTPort) - Constructor for class lejos.hardware.sensor.EV3ColorSensor
 
EV3ColorSensor(Port) - Constructor for class lejos.hardware.sensor.EV3ColorSensor
 
EV3GyroSensor - Class in lejos.hardware.sensor
EV3 Gyro sensor
The digital EV3 Gyro Sensor measures the sensors rotational motion and changes in its orientation.
EV3GyroSensor(Port) - Constructor for class lejos.hardware.sensor.EV3GyroSensor
 
EV3GyroSensor(UARTPort) - Constructor for class lejos.hardware.sensor.EV3GyroSensor
 
EV3IRSensor - Class in lejos.hardware.sensor
EV3 Infra Red sensor
The digital EV3 Infrared Seeking Sensor detects proximity to the robot and reads signals emitted by the EV3 Infrared Beacon.
EV3IRSensor(UARTPort) - Constructor for class lejos.hardware.sensor.EV3IRSensor
 
EV3IRSensor(Port) - Constructor for class lejos.hardware.sensor.EV3IRSensor
 
EV3LargeRegulatedMotor - Class in lejos.hardware.motor
Abstraction for a Large Lego EV3/NXT motor.
EV3LargeRegulatedMotor(TachoMotorPort) - Constructor for class lejos.hardware.motor.EV3LargeRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
EV3LargeRegulatedMotor(Port) - Constructor for class lejos.hardware.motor.EV3LargeRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
EV3MediumRegulatedMotor - Class in lejos.hardware.motor
Abstraction for a Medium Lego EV3/NXT motor.
EV3MediumRegulatedMotor(TachoMotorPort) - Constructor for class lejos.hardware.motor.EV3MediumRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
EV3MediumRegulatedMotor(Port) - Constructor for class lejos.hardware.motor.EV3MediumRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
EV3NavigationModel - Class in lejos.robotics.mapping
NXT version of the navigation model.
EV3NavigationModel() - Constructor for class lejos.robotics.mapping.EV3NavigationModel
Create the model and start the receiver thread
EV3Reply - Class in lejos.remote.ev3
 
EV3Reply() - Constructor for class lejos.remote.ev3.EV3Reply
 
EV3Request - Class in lejos.remote.ev3
 
EV3Request() - Constructor for class lejos.remote.ev3.EV3Request
 
EV3Request.Request - Enum in lejos.remote.ev3
 
EV3SensorConstants - Interface in lejos.hardware.sensor
Basic constants for use when accessing EV3 Sensors.
EV3TouchSensor - Class in lejos.hardware.sensor
Lego EV3 Touch sensor
The analog EV3 Touch Sensor is a simple but exceptionally precise tool that detects when its front button is pressed or released.
EV3TouchSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.EV3TouchSensor
 
EV3TouchSensor(Port) - Constructor for class lejos.hardware.sensor.EV3TouchSensor
 
EV3UltrasonicSensor - Class in lejos.hardware.sensor
Lego EV3 Ultrasonic sensor
The EV3 Ultrasonic sensor measures distance to an object in front of the sensor.
EV3UltrasonicSensor(Port) - Constructor for class lejos.hardware.sensor.EV3UltrasonicSensor
Create the Ultrasonic sensor class.
EV3UltrasonicSensor(UARTPort) - Constructor for class lejos.hardware.sensor.EV3UltrasonicSensor
Create the Ultrasonic sensor class.
eventReceived(NavigationModel.NavEvent) - Method in interface lejos.robotics.mapping.NavEventListener
 

F

FAHRENHEITMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
fatal(String) - Method in class lejos.robotics.mapping.EV3NavigationModel
Display a fatal error and shut down the program
feature - Variable in class lejos.robotics.mapping.NavigationModel
 
Feature - Interface in lejos.robotics.objectdetection
A Feature is an interface for information retrieved about an object detected by sensors.
featureDetected(Feature, FeatureDetector) - Method in class lejos.robotics.mapping.EV3NavigationModel
Called when a feature is detected.
featureDetected(Feature, FeatureDetector) - Method in interface lejos.robotics.objectdetection.FeatureListener
The angle and range (in a RangeReading) of a feature is reported when a feature is detected.
featureDetected(Feature, FeatureDetector) - Method in class lejos.robotics.objectdetection.FusorDetector
This method must deal with different delays from different sensors.
FeatureDetector - Interface in lejos.robotics.objectdetection
A FeatureDetector is capable of detecting objects and notifying listeners when it detects something.
FeatureDetectorAdapter - Class in lejos.robotics.objectdetection
An adapter to make it easier to implement FeatureDetector classes.
FeatureDetectorAdapter(int) - Constructor for class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
FeatureListener - Interface in lejos.robotics.objectdetection
Any class implementing this interface and registering with a FeatureDetector will receive notifications when a feature is detected.
fetch() - Method in class lejos.robotics.filter.FilterTerminal
 
fetchFile(String) - Method in interface lejos.remote.ev3.Menu
 
fetchFile(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
fetchFile(String) - Method in interface lejos.remote.ev3.RMIMenu
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.BaseSensor
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.DexterIMUSensor.DexterIMUAccelerationSensor
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.HiTechnicColorSensor.RGBMode
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.HiTechnicEOPD.ShortDistanceMode
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.NXTSoundSensor.DBMode
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.NXTUltrasonicSensor.DistanceMode
 
fetchSample(float[], int) - Method in class lejos.hardware.sensor.NXTUltrasonicSensor.PingMode
 
fetchSample(float[], int) - Method in class lejos.remote.ev3.RemoteRequestSampleProvider
 
fetchSample() - Method in class lejos.remote.ev3.RMIRemoteSampleProvider
 
fetchSample() - Method in interface lejos.remote.ev3.RMISampleProvider
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Fetches a sample from the sensor and updates array with minimum and maximum values when the calibration process is running.
fetchSample(float[], int) - Method in class lejos.robotics.filter.AbstractFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.ConcatenationFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.Dump
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.IntegrationFilter
Fetches a sample from the source and then integrates it.
fetchSample(float[], int) - Method in class lejos.robotics.filter.LinearCalibrationFilter
Fetches a sample from the sensor and updates calibration parameters when the calibration process is running.
fetchSample(float[], int) - Method in class lejos.robotics.filter.LowPassFilter
Fetches a sample from the source and low-passes it See http://en.wikipedia.org/wiki/Low-pass_filter
fetchSample(float[], int) - Method in class lejos.robotics.filter.MaximumFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.MeanFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.MedianFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.MinimumFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.ModulusFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.OffsetCorrectionFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.PublishFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.SampleBuffer
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.SampleThread
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.SliceFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.SubscribedProvider
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.SumFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.filter.ZeroFilter
 
fetchSample(float[], int) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
fetchSample(float[], int) - Method in interface lejos.robotics.SampleProvider
Fetches a sample from a sensor or filter.
fetchString(byte, int) - Method in class lejos.hardware.sensor.I2CSensor
Read a string from the device.
fetchString(byte, int) - Method in class lejos.hardware.sensor.RFIDSensor
We over-ride the default implementation to ensure that the device is awake before we talk to it.
FIELD_ANY - Static variable in interface lejos.hardware.video.Video
 
FIELD_INTERLACED - Static variable in interface lejos.hardware.video.Video
 
FIELD_NONE - Static variable in interface lejos.hardware.video.Video
 
file - Variable in class lejos.remote.ev3.EV3Request
 
FILE_EXISTS - Static variable in class lejos.remote.nxt.ErrorMessages
 
FILE_IS_BUSY - Static variable in class lejos.remote.nxt.ErrorMessages
 
FILE_IS_FULL - Static variable in class lejos.remote.nxt.ErrorMessages
 
FILE_NOT_FOUND - Static variable in class lejos.remote.nxt.ErrorMessages
 
fileHandle - Variable in class lejos.remote.nxt.FileInfo
The handle for accessing the file.
FileInfo - Class in lejos.remote.nxt
Structure that gives information about a leJOS NXJ file.
FileInfo(String) - Constructor for class lejos.remote.nxt.FileInfo
 
fileName - Variable in class lejos.remote.nxt.FileInfo
The name of the file - up to 20 characters.
fileSize - Variable in class lejos.remote.nxt.FileInfo
The size of the file in bytes.
fillArc(int, int, int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a filled arc, using the current color.
fillArc(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
fillArc(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
fillArc(int, int, int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
fillArc(int, int, int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
fillRect(int, int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Draw a filled rectangle using the current color.
fillRect(int, int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
fillRect(int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
fillRect(int, int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
fillRect(int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
FilterTerminal - Class in lejos.robotics.filter
 
FilterTerminal(SampleProvider) - Constructor for class lejos.robotics.filter.FilterTerminal
 
find(String) - Static method in class lejos.hardware.BrickFinder
Search for a named EV3.
FIND_FIRST - Static variable in class lejos.remote.nxt.LCP
 
FIND_FIRST - Static variable in interface lejos.remote.nxt.NXTProtocol
 
FIND_NEXT - Static variable in class lejos.remote.nxt.LCP
 
FIND_NEXT - Static variable in interface lejos.remote.nxt.NXTProtocol
 
findCircleCenter(Point, float, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Calculates the center of a circle that rests on the tangent of the vehicle's starting heading.
findClosest(float, float) - Method in class lejos.robotics.localization.MCLParticleSet
Find the index of the particle closest to a given co-ordinates.
finder - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
findFirst(String) - Method in class lejos.remote.nxt.NXTCommand
Find the first file on the NXT.
findNext(byte) - Method in class lejos.remote.nxt.NXTCommand
Find the next file on the NXT
findP2(Point, Point, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method finds P2 if the vehicle is traveling to a point (with no heading).
findPath(Node, Node) - Method in class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
findPath(Node, Node) - Method in interface lejos.robotics.pathfinding.SearchAlgorithm
Method accepts a start node and a goal node, and returns a path consisting of a collection of waypoints which includes the startNode coordinates as the first waypoint, and the goal node coordinates as the final waypoint.
findPointOnHeading(Point, float, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Given a starting point and heading, this method will calculate another Point that is distance away from the first point.
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
Finds the shortest path from start to finish using the map (or collection of lines) in the constructor.
findRoute(Pose, Waypoint, LineMap) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
Finds the shortest path from start to finish using the map (or collection of lines) in the constructor.
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.NodePathFinder
 
findRoute(Pose, Waypoint) - Method in interface lejos.robotics.pathfinding.PathFinder
 
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.RandomPathFinder
 
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
Finds the shortest path from start to finish using the map (or collection of lines) in the constructor.
findRoute(Pose, Waypoint, LineMap) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
Finds the shortest path from start to finish using the map ( collection of lines) in the constructor.
FirmwareInfo - Class in lejos.remote.nxt
Firmware information for a remote NXT accessed via LCP.
FirmwareInfo() - Constructor for class lejos.remote.nxt.FirmwareInfo
 
firmwareMajorVersion - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
firmwareMinorVersion - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
firmwarePatchLevel - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
firmwareRevision - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
firmwareVersion - Variable in class lejos.remote.nxt.FirmwareInfo
 
firstChar - Variable in class lejos.hardware.lcd.Font
 
FixedRangeScanner - Class in lejos.robotics
 
FixedRangeScanner(RotateMoveController, RangeFinder) - Constructor for class lejos.robotics.FixedRangeScanner
 
flag - Variable in class lejos.remote.ev3.EV3Request
 
flip() - Method in class lejos.robotics.mapping.LineMap
Create a line map with the y axis flipped
FLOAT - Static variable in interface lejos.hardware.port.BasicMotorPort
Motor is floating (no PWM drive)
Float() - Constructor for class lejos.robotics.geometry.Line2D.Float
Creates a zero length line at (0,0)
Float(float, float, float, float) - Constructor for class lejos.robotics.geometry.Line2D.Float
Create a line from (x1,y1) to (x2,y2)
Float() - Constructor for class lejos.robotics.geometry.Point2D.Float
Create a point at (0,0) with float coordinates
Float(float, float) - Constructor for class lejos.robotics.geometry.Point2D.Float
Create a point at (x,y) with float coordinates
Float() - Constructor for class lejos.robotics.geometry.Rectangle2D.Float
Create an empty rectangle at (0,0)
Float(float, float, float, float) - Constructor for class lejos.robotics.geometry.Rectangle2D.Float
Create a rectangle with float coordinates
floatReply - Variable in class lejos.remote.ev3.EV3Reply
 
floats - Variable in class lejos.remote.ev3.EV3Reply
 
floatValue - Variable in class lejos.remote.ev3.EV3Request
 
flt() - Method in class lejos.hardware.device.MMXMotor
 
flt(boolean) - Method in class lejos.hardware.device.MMXRegulatedMotor
 
flt() - Method in class lejos.hardware.device.PFMateMotor
Floats the motor
flt() - Method in class lejos.hardware.device.tetrix.TetrixMotor
 
flt(boolean) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
flt() - Method in class lejos.hardware.device.tetrix.TetrixServoController
Set all servos connected to this controller to float mode.
flt() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Set the motor into float mode.
flt(boolean) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Set the motor into float mode.
flt() - Method in class lejos.hardware.motor.BasicMotor
Causes motor to float.
flt() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
flt(boolean) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
flt(boolean) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Set the motor into float mode.
flt(boolean) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
flt() - Method in interface lejos.robotics.BaseMotor
Motor loses all power, causing the rotor to float freely to a stop.
flt(boolean) - Method in class lejos.robotics.MirrorMotor
 
flt() - Method in class lejos.robotics.MirrorMotor
 
flt(boolean) - Method in interface lejos.robotics.RegulatedMotor
Set the motor into float mode.
fltMotor(int) - Method in class lejos.hardware.device.RCXLink
 
fltMotors() - Method in class lejos.hardware.device.NXTMMX
Synchronized Float both motors
flush() - Method in class lejos.hardware.device.RCXLink
 
flush() - Method in class lejos.remote.nxt.NXTOutputStream
 
FLUTE - Static variable in interface lejos.hardware.Sounds
 
followPath(Path) - Method in class lejos.robotics.navigation.Navigator
Starts the robot traversing the path.
followPath() - Method in class lejos.robotics.navigation.Navigator
Starts the robot traversing the current path.
Font - Class in lejos.hardware.lcd
Provides access to fonts for use with the display or images.
Font(byte[], int, int, int, int, int, int) - Constructor for class lejos.hardware.lcd.Font
Create a new font for the specified NXT format glyph map
FONT_HEIGHT - Static variable in class lejos.hardware.lcd.LCD
 
FONT_WIDTH - Static variable in class lejos.hardware.lcd.LCD
 
format - Static variable in class lejos.robotics.navigation.Pose
 
formatter - Variable in class lejos.robotics.filter.PublishedSource
 
formatter - Variable in class lejos.robotics.filter.SubscribedProvider
 
forward() - Method in class lejos.hardware.device.LServo
Classic forward method for continous RC Servos
forward() - Method in class lejos.hardware.device.MMXMotor
 
forward() - Method in class lejos.hardware.device.PFMateMotor
Runs the motor forward
forward(int) - Method in class lejos.hardware.device.RCXLink
 
forward() - Method in class lejos.hardware.device.tetrix.TetrixMotor
 
forward() - Method in class lejos.hardware.motor.BaseRegulatedMotor
 
forward() - Method in class lejos.hardware.motor.BasicMotor
Causes motor to rotate forward.
FORWARD - Static variable in interface lejos.hardware.port.BasicMotorPort
Motor is running forward
forward() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
forward() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
forward() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
 
forward() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
forward() - Method in interface lejos.robotics.BaseMotor
Causes motor to rotate forward until stop() or flt() is called.
forward - Variable in class lejos.robotics.chassis.WheeledChassis
 
forward() - Method in class lejos.robotics.MirrorMotor
 
forward() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Starts the NXT robot moving forward.
forward() - Method in interface lejos.robotics.navigation.MoveController
Starts the NXT robot moving forward.
forward() - Method in class lejos.robotics.navigation.MovePilot
 
forward() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
forward() - Method in class lejos.robotics.navigation.SteeringPilot
 
forwardAbs - Variable in class lejos.robotics.chassis.WheeledChassis
 
forwardStep(int) - Method in class lejos.hardware.device.IRLink
 
forwardStep(int) - Method in interface lejos.hardware.device.IRTransmitter
 
forwardStep(int) - Method in class lejos.hardware.device.RCXLink
 
fourcc(char, char, char, char) - Static method in class lejos.hardware.video.VideoUtils
 
FourWayGridMesh - Class in lejos.robotics.pathfinding
Generates a grid of nodes.
FourWayGridMesh(LineMap, float, float) - Constructor for class lejos.robotics.pathfinding.FourWayGridMesh
Instantiates a grid mesh of nodes which won't interconnect between any map geometry.
freeFlash - Variable in class lejos.remote.nxt.DeviceInfo
 
FREQ_SETTING - Static variable in class lejos.hardware.Button
 
FREQ_SETTING - Static variable in interface lejos.hardware.Keys
 
frequency - Variable in class lejos.robotics.filter.PublishedSource
 
frequency - Variable in class lejos.robotics.filter.PublishFilter
 
FusorDetector - Class in lejos.robotics.objectdetection
If you have a robot with multiple sensors (touch and range) and would like them to report to one listener, or if you want to control them at the same time (such as disabling them all at once) you can use this class.
FusorDetector() - Constructor for class lejos.robotics.objectdetection.FusorDetector
 

G

g - Static variable in class lejos.hardware.lcd.LCD
 
gearRatio - Variable in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
gearRatio(double) - Method in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
Defines the gear train between motor and wheel.
gearRatio - Variable in class lejos.robotics.chassis.WheeledChassis.Modeler
 
gearRatio(double) - Method in class lejos.robotics.chassis.WheeledChassis.Modeler
Defines the gear train between motor and wheel.
gearRatio - Variable in class lejos.robotics.RotatingRangeScanner
 
generateParticles() - Method in class lejos.robotics.localization.MCLPoseProvider
Generate a new particle set, uniformly distributed within the map, and uniformly distributed heading.
get() - Static method in class lejos.hardware.ev3.LocalEV3
 
get(String, NXTCommConnector) - Static method in class lejos.remote.nxt.RemoteNXT
 
get(int, int) - Method in class lejos.utility.Matrix
Get a single element.
GET_BATTERY_LEVEL - Static variable in class lejos.remote.nxt.LCP
 
GET_BATTERY_LEVEL - Static variable in interface lejos.remote.nxt.NXTProtocol
 
GET_CURRENT_PROGRAM_NAME - Static variable in class lejos.remote.nxt.LCP
 
GET_CURRENT_PROGRAM_NAME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
GET_DEVICE_INFO - Static variable in class lejos.remote.nxt.LCP
 
GET_DEVICE_INFO - Static variable in interface lejos.remote.nxt.NXTProtocol
 
GET_FIRMWARE_VERSION - Static variable in class lejos.remote.nxt.LCP
 
GET_FIRMWARE_VERSION - Static variable in interface lejos.remote.nxt.NXTProtocol
 
GET_INPUT_VALUES - Static variable in class lejos.remote.nxt.LCP
 
GET_INPUT_VALUES - Static variable in interface lejos.remote.nxt.NXTProtocol
 
GET_OUTPUT_STATE - Static variable in class lejos.remote.nxt.LCP
 
GET_OUTPUT_STATE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
getAcceleration() - Method in class lejos.hardware.motor.BaseRegulatedMotor
returns acceleration in degrees/second/second
getAccelerationMode() - Method in class lejos.hardware.sensor.CruizcoreGyro
Cruizcore XG1300L, Acceleration mode
Measures linear acceleration over three axes
getAccelerationMode() - Method in class lejos.hardware.sensor.DexterIMUSensor
Dexter Industries dIMU Sensor, Acceleration Mode
The Acceleration mode measures the linear acceleration of the sensor over three axes
getAccelerationMode() - Method in class lejos.hardware.sensor.HiTechnicAccelerometer
HiTechnic NXT Acceleration , Acceleration mode
Measures acceleration over three axes.
getAccelerationMode() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Return a SensorMode object that will acceleration data for the X, Y and Z axis.
getAccelerationMode() - Method in class lejos.hardware.sensor.MindsensorsAccelerometer
Return a SampleProvider that provides acceleration data (in m/s/s) in X, Y, Z axis
getAccessPoint() - Method in class lejos.hardware.LocalWifiDevice
 
getAccessPoint() - Method in class lejos.remote.ev3.RMIRemoteWifi
 
getAccessPoint() - Method in interface lejos.remote.ev3.RMIWifi
 
getAccessPointNames() - Method in class lejos.hardware.LocalWifiDevice
 
getAccessPointNames() - Method in class lejos.remote.ev3.RMIRemoteWifi
 
getAccessPointNames() - Method in interface lejos.remote.ev3.RMIWifi
 
getAccumulatedAngleMode() - Method in class lejos.hardware.sensor.HiTechnicAngleSensor
HiTechnic angle sensor, Accumulated angle mode
Measures the accumulated number of degrees an axle has rotated.
getActualSize() - Method in class lejos.robotics.filter.SampleBuffer
 
getActualSize() - Method in class lejos.robotics.filter.SumFilter
 
getAddress(String) - Static method in class lejos.hardware.Bluetooth
Return a Bluetooth binary address given a String version of the address
getAddress(byte[]) - Static method in class lejos.hardware.Bluetooth
Return a String version of a Bluetooth address given a binary address
getAddress() - Method in class lejos.hardware.RemoteBTDevice
 
getAddress() - Method in class lejos.hardware.sensor.I2CSensor
Return the the I2C address of the sensor.
getAddress() - Static method in class lejos.remote.nxt.NXTCommDevice
Return the current USB serial number.
getAltitude() - Method in class lejos.hardware.gps.Coordinates
Altitude above mean sea level.
getAltitude() - Method in class lejos.hardware.gps.GGASentence
Get Altitude
getAltitude() - Method in class lejos.hardware.gps.SimpleGPS
The altitude above mean sea level
getAmbientMode() - Method in class lejos.hardware.sensor.DexterLaserSensor
Dexter laser sensor, Ambient mode
Measures light level with the laser off
getAmbientMode() - Method in class lejos.hardware.sensor.DexterThermalIRSensor
Dexter Industries Thermal Infrared Sensor, Ambient mode
Measures the ambient temperature
getAmbientMode() - Method in class lejos.hardware.sensor.EV3ColorSensor
EV3 color sensor, Ambient mode
Measures the level of ambient light while the sensors lights are off.
getAmbientMode() - Method in class lejos.hardware.sensor.NXTColorSensor
get a sample provider the returns the light value when illuminated without a light source.
getAmbientMode() - Method in class lejos.hardware.sensor.NXTLightSensor
get a sample provider the returns the light value when illuminated without a light source.
getAmbientMode() - Method in class lejos.hardware.sensor.RCXLightSensor
get a sample provider the returns the light value when illuminated without a light source.
getAMPM() - Method in interface lejos.robotics.Clock
 
getAnalogSensorType(int) - Static method in class lejos.remote.nxt.RemoteNXTAnalogPort
Get the type of analog sensor (if any) attached to the port
getAngle() - Method in class lejos.hardware.device.LServo
Method to know the angle
getAngle() - Method in class lejos.hardware.device.MServo
Return the angle used in last operation
getAngle() - Method in class lejos.hardware.device.tetrix.TetrixServo
Returns the current servo angle as reverse calculated by the last call to setAngle().
getAngle() - Method in interface lejos.robotics.Gyroscope
 
getAngle() - Method in class lejos.robotics.GyroscopeAdapter
 
getAngle() - Method in class lejos.robotics.RangeReading
Get the angle of the range reading
getAngle(int) - Method in class lejos.robotics.RangeReadings
Get the angle of a specific reading
getAngle() - Method in interface lejos.robotics.Servo
Gets the rotational position (angle) of a ranged servo.
getAngleAndRateMode() - Method in class lejos.hardware.sensor.EV3GyroSensor
EV3 Gyro sensor, Rate mode
Measures both angle and angular velocity of the sensor.
getAngleIncrement() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Returns the change in robot heading since the last call of reset() normalized to be within -180 and _180 degrees
getAngleIncrement() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getAngleMode() - Method in class lejos.hardware.sensor.CruizcoreGyro
Cruizcore XG1300L, Angle mode
Measures angle over the Z-axis
getAngleMode() - Method in class lejos.hardware.sensor.DexterGPSSensor
Dexter dGPS sensor, Angle mode
Gets the heading of the sensor
getAngleMode() - Method in class lejos.hardware.sensor.EV3GyroSensor
EV3 Gyro sensor, Angle mode
Measures the orientation of the sensor in respect to its start orientation.
getAngleMode() - Method in class lejos.hardware.sensor.HiTechnicAngleSensor
HiTechnic angle sensor, Angle mode
Measures the rotation position of a rotating axle.
getAngleMode() - Method in class lejos.hardware.sensor.HiTechnicCompass
HiTechnic compass sensor, Angle mode
Measures the color of a surface.
getAngleMode() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Return a SensorMode object that will provide angle data.
getAngleMode() - Method in class lejos.hardware.sensor.MindsensorsCompass
MindSensors compass sensor, Angle mode
Measures the bearing of the sensor.
getAngleTurned() - Method in class lejos.robotics.navigation.Move
Get the angle turned by a rotate or an arc operation.
getAngularAcceleration() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getAngularAcceleration() - Method in interface lejos.robotics.chassis.Chassis
Gets the setting for angular acceleration as is used in travel, arc, rotate and setvelocity methods
getAngularAcceleration() - Method in class lejos.robotics.chassis.WheeledChassis
 
getAngularAcceleration() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getAngularAcceleration() - Method in class lejos.robotics.navigation.MovePilot
 
getAngularAcceleration() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getAngularAcceleration() - Method in interface lejos.robotics.navigation.RotateMoveController
Returns the acceleration at which the robot accelerates at the start of a move and decelerates at the end of a move.
getAngularAcceleration() - Method in class lejos.utility.GyroDirectionFinder
Returns the current rate at which the angular velocity is increasing or decreasing in degrees-per-second, per second.
getAngularSpeed() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getAngularSpeed() - Method in interface lejos.robotics.chassis.Chassis
Gets the setting for angular speed as is used in travel, arc, and rotate methods
getAngularSpeed() - Method in class lejos.robotics.chassis.WheeledChassis
 
getAngularSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getAngularSpeed() - Method in class lejos.robotics.navigation.MovePilot
 
getAngularSpeed() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getAngularSpeed() - Method in interface lejos.robotics.navigation.RotateMoveController
Returns the value of the rotation speed
getAngularVelocity() - Method in interface lejos.robotics.chassis.Chassis
Returns the angular component of the current speed of the robot
getAngularVelocity() - Method in class lejos.robotics.chassis.WheeledChassis
 
getAngularVelocity() - Method in interface lejos.robotics.Gyroscope
Implementor must calculate and return the angular velocity in degrees per second.
getAngularVelocity() - Method in class lejos.robotics.GyroscopeAdapter
 
getAngularVelocity() - Method in class lejos.utility.GyroDirectionFinder
Returns the current rate-of-turn in degrees/second, as read by the GyroSensor instance passed in the constructor.
getAngularVelocityMode() - Method in class lejos.hardware.sensor.HiTechnicAngleSensor
HiTechnic angle sensor, Angular velocity mode
Measures the rotational speed of an axle.
getArc(Point, Point, float, float, boolean) - Static method in class lejos.robotics.navigation.ArcAlgorithms
If p1 is the starting point of the robot, and p2 is the point at which the robot is pointing directly at the target point, this method calculates the angle to travel along the circle (an arc) to get from p1 to p2.
getArcBackward(float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Quick calculation of reverse arc instead of going through getArcLength() math again.
getArcOld(Point, Point, double) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Deprecated.
This method is no longer used because it can't calculate >180 angles. Delete any time.
getArcRadius() - Method in class lejos.robotics.navigation.Move
Get the radius of the arc
getArray() - Method in class lejos.utility.Matrix
Access the internal two-dimensional array.
getArrayCopy() - Method in class lejos.utility.Matrix
Copy the internal two-dimensional array.
getAttribute(int) - Method in class lejos.robotics.chassis.WheeledChassis
Helper method to get some dynamic attributes from each motor
getAudio() - Method in interface lejos.hardware.Brick
return a Audio object which can be used to access the device's audio playback
getAudio() - Method in class lejos.hardware.ev3.LocalEV3
return a Audio object which can be used to access the device's audio playback
getAudio() - Method in class lejos.remote.ev3.RemoteEV3
 
getAudio() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getAudio() - Method in interface lejos.remote.ev3.RMIEV3
 
getAudio() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getAudio() - Method in class lejos.remote.nxt.RemoteNXT
 
getAutoRun() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to get the auto run setring
getAvailableModes() - Method in class lejos.hardware.sensor.BaseSensor
 
getAvailableModes() - Method in interface lejos.hardware.sensor.SensorModes
Return a list of string descriptions for the sensors available modes.
getAvailablePaths(Pose, float, Pose, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method gets all the available paths given a start Pose and destination Post.
getAvailablePaths(Pose, Point, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method calculates the moves needed to drive from a starting Pose to a final Point.
getAzimuth() - Method in class lejos.hardware.gps.Satellite
Direction to the satellite in degrees.
getBaselinePosition() - Method in class lejos.hardware.lcd.Font
Return the base line position in pixels.
getBasicMotor(int) - Method in class lejos.hardware.device.NXTMMX
Get a MMXMotor instance that is associated with the motorID.
getBasicMotor(int) - Method in class lejos.hardware.device.tetrix.TetrixMotorController
Get a TetrixMotor instance that is associated with the motorID.
getBattery() - Method in class lejos.hardware.device.MSC
Read the battery voltage data from NXTServo module (in millivolts)
getBattery() - Method in interface lejos.remote.ev3.RMIEV3
 
getBattery() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getBatteryCurrent() - Static method in class lejos.hardware.Battery
 
getBatteryCurrent() - Method in interface lejos.hardware.Power
Return the current draw from the battery
getBatteryCurrent() - Method in class lejos.remote.ev3.RemoteBattery
 
getBatteryCurrent() - Method in class lejos.remote.ev3.RemoteRequestBattery
 
getBatteryCurrent() - Method in interface lejos.remote.ev3.RMIBattery
Return the current draw from the battery
getBatteryCurrent() - Method in class lejos.remote.ev3.RMIRemoteBattery
 
getBatteryCurrent() - Method in class lejos.remote.nxt.RemoteNXTBattery
 
getBatteryLevel() - Method in class lejos.remote.nxt.NXTCommand
Get the battery reading
getBest(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
Helper method for findPath()
returns the node in the Reached set, whose distance from the start node plus its straight line distance to the destination is the minimum.
getBestPath(Pose, float, Pose, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Find the shortest path for a steering vehicle between two points.
getBestPath(Pose, Point, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method generates the shortest path from a starting Pose to a final Point.
getBestPath(Move[][]) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This helper method accepts a number of paths (an array of Move) and selects the shortest path.
getBlue() - Method in class lejos.robotics.Color
Returns the blue component in the range 0-255 in the default sRGB space.
getBlueMode() - Method in class lejos.hardware.sensor.NXTColorSensor
get a sample provider the returns the light value when illuminated with a Blue light source.
getBluetooth() - Method in class lejos.remote.ev3.RemoteEV3
 
getBluetooth() - Method in interface lejos.remote.ev3.RMIEV3
 
getBluetooth() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getBluetoothAddress() - Method in class lejos.hardware.LocalBTDevice
Return the address of the local device
getBluetoothAddress() - Method in interface lejos.remote.ev3.RMIBluetooth
 
getBluetoothAddress() - Method in class lejos.remote.ev3.RMIRemoteBluetooth
 
getBluetoothDevice() - Method in interface lejos.hardware.Brick
Get the local Bluetooth device
getBluetoothDevice() - Method in class lejos.hardware.ev3.LocalEV3
 
getBluetoothDevice() - Method in class lejos.remote.ev3.RemoteEV3
 
getBluetoothDevice() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getBluetoothDevice() - Method in class lejos.remote.nxt.RemoteNXT
 
getBorder() - Method in class lejos.robotics.localization.MCLParticleSet
Get the border where particles should not be generated
getBoundingRect() - Method in class lejos.robotics.mapping.LineMap
Return the bounding rectangle of the mapped area
getBoundingRect() - Method in interface lejos.robotics.mapping.RangeMap
Get the bounding rectangle for the mapped area
getBounds() - Method in class lejos.robotics.geometry.Line2D
 
getBounds() - Method in class lejos.robotics.geometry.RectangleInt32
 
getBounds() - Method in class lejos.robotics.geometry.RectangularShape
Get the bounds of this rectangular shape as a Rectangle
getBounds() - Method in interface lejos.robotics.geometry.Shape
Get the bounding Rectangle for the shape
getBounds2D() - Method in class lejos.robotics.geometry.Line2D.Double
Get the bounds of the line as a Rectangle2D
getBounds2D() - Method in class lejos.robotics.geometry.Line2D.Float
Get the bounds of the line as a Rectangle2D
getBounds2D() - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
getBounds2D() - Method in class lejos.robotics.geometry.Rectangle2D.Float
Get the bounds as a Rectangle2D with float coordinates
getBounds2D() - Method in class lejos.robotics.geometry.RectangleInt32
 
getBounds2D() - Method in interface lejos.robotics.geometry.Shape
Get the bounding Rectangle2D for the shape
getBufferSize() - Method in class lejos.robotics.filter.SampleBuffer
 
getButtons() - Static method in class lejos.hardware.Button
Low-level API that reads status of buttons.
getButtons() - Method in class lejos.hardware.device.PSPNXController
Each bit in the short byte represents the boolean (pressed or not pressed) of a button.
getButtons() - Method in interface lejos.hardware.Keys
 
getButtons() - Method in class lejos.remote.ev3.RemoteKeys
 
getButtons() - Method in class lejos.remote.ev3.RemoteRequestKeys
 
getButtons() - Method in interface lejos.remote.ev3.RMIKeys
 
getButtons() - Method in class lejos.remote.ev3.RMIRemoteKeys
 
getByte() - Method in interface lejos.hardware.port.UARTPort
read a single byte from the device
getByte() - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
getByte() - Method in class lejos.remote.ev3.RemoteUARTPort
 
getByte() - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
getByte() - Method in interface lejos.remote.ev3.RMIUARTPort
read a single byte from the device
getByte(int) - Method in interface lejos.robotics.Clock
 
getBytes(byte[], int, int) - Method in interface lejos.hardware.port.UARTPort
read a number of bytes from the device
getBytes(byte[], int, int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
getBytes(byte[], int, int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
getBytes(byte[], int, int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
getBytes(byte[], int, int) - Method in interface lejos.remote.ev3.RMIUARTPort
read a number of bytes from the device
getCalibrationMetric() - Method in class lejos.hardware.sensor.HiTechnicBarometer
 
getCalibrationType() - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
getCallibrationType() - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
getCenterX() - Method in class lejos.robotics.geometry.RectangularShape
Get the x coordinate of the center of the shape
getCenterY() - Method in class lejos.robotics.geometry.RectangularShape
Get the y coordinate of the center of the shape
getChanged() - Method in class lejos.remote.nxt.RemoteNXTI2CPort
 
getChannel() - Method in class lejos.hardware.device.PFMate
Returns the current IR channel in use by the PF Mate
getColor(int[]) - Method in interface lejos.hardware.device.DLight
Returns the RGB color of the LED Each of the color values is between 0 (fully off) and 255 (fully on).
getColor(int, int[]) - Method in class lejos.hardware.device.DLights
Returns the RGB color of the LED Each of the color values is between 0 (fully off) and 255 (fully on).
getColor() - Method in class lejos.robotics.Color
 
getColor() - Method in class lejos.robotics.ColorAdapter
 
getColor() - Method in interface lejos.robotics.ColorDetector
Return the Red, Green and Blue values together in one object.
getColorID() - Method in class lejos.hardware.sensor.EV3ColorSensor
Return an enumerated constant that indicates the color detected.
getColorID() - Method in class lejos.hardware.sensor.HiTechnicColorSensor
Returns the color index detected by the sensor.
getColorID() - Method in class lejos.hardware.sensor.NXTColorSensor
Read the current color and return an enumeration constant.
getColorID() - Method in class lejos.robotics.ColorAdapter
 
getColorID() - Method in interface lejos.robotics.ColorIdentifier
Return an enumerated constant that indicates the color detected.
getColorIDMode() - Method in class lejos.hardware.sensor.EV3ColorSensor
EV3 color sensor, Color ID mode
Measures the color ID of a surface.
getColorIDMode() - Method in class lejos.hardware.sensor.HiTechnicColorSensor
HiTechnic color sensor, Color ID mode
Measures the color ID of a surface.
getColorIDMode() - Method in class lejos.hardware.sensor.NXTColorSensor
get a sample provider in color ID mode
getColumnDimension() - Method in class lejos.utility.Matrix
Get column dimension.
getColumnPackedCopy() - Method in class lejos.utility.Matrix
Make a one-dimensional column packed copy of the internal array.
getCompass() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Return the compass
getCompassDegrees() - Method in class lejos.hardware.gps.GPS
Return Compass Degrees in a range: 0.0-359.9
getCompassDegrees() - Method in class lejos.hardware.gps.RMCSentence
Return compass value from GPS
getCompassHeading() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Method returns the current compass heading
getCompassMode() - Method in class lejos.hardware.sensor.HiTechnicCompass
HiTechnic compass sensor, Compass mode
Measures the bearing of the sensor.
getCompassMode() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Return a SensorMode object that will provide tilt compensated compass data .
getCompassMode() - Method in class lejos.hardware.sensor.MindsensorsCompass
Mindsensors compass sensor, Compass mode
Measures the bearing of the sensor.
getCourse() - Method in class lejos.hardware.gps.SimpleGPS
Get the course heading of the GPS unit.
getCovariance() - Method in class lejos.utility.KalmanFilter
 
getCurrentMode() - Method in class lejos.hardware.sensor.BaseSensor
 
getCurrentMode() - Method in interface lejos.hardware.sensor.SensorModes
Gets the index number of the current mode.
getCurrentProgramName() - Method in class lejos.remote.nxt.NXTCommand
Name of current running program.
getCurrentSpeed() - Method in interface lejos.robotics.chassis.Chassis
Returns a matrix containing the current speed of the robot.
getCurrentSpeed() - Method in class lejos.robotics.chassis.WheeledChassis
 
getCurrentVelocity() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
getCurrentVelocity() - Method in interface lejos.hardware.motor.MotorRegulator
Return the current velocity (in degrees/second) that the motor is currently running at.
getData() - Method in class lejos.hardware.lcd.Image
Return the byte array used to hold the image data.
getData(int, byte[], int) - Method in class lejos.hardware.sensor.I2CSensor
Executes an I2C read transaction and waits for the result.
getData(int, byte[], int, int) - Method in class lejos.hardware.sensor.I2CSensor
Executes an I2C read transaction and waits for the result.
getData(int, byte[], int, int) - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
 
getDate() - Method in class lejos.hardware.gps.GPS
Return a Date Object with data from GGA and RMC NMEA Sentence
getDate() - Method in class lejos.hardware.gps.RMCSentence
Get date in integer format
getDateString() - Method in interface lejos.robotics.Clock
 
getDay() - Method in interface lejos.robotics.Clock
 
getDayOfWeek() - Method in interface lejos.robotics.Clock
 
getDBAMode() - Method in class lejos.hardware.sensor.NXTSoundSensor
get a sample provider the returns the sound level adjusted to how a human ear would experience it
getDBMode() - Method in class lejos.hardware.sensor.NXTSoundSensor
get a sample provider the returns the sound level
getDCMotor(int) - Method in class lejos.hardware.device.LSC
Method to get an LDC Motor
getDefault() - Static method in class lejos.hardware.BrickFinder
 
getDefaultFont() - Static method in class lejos.hardware.lcd.Font
Return the system font.
getDefaultProgram() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to get the default program name
getDegrees() - Method in class lejos.utility.GyroDirectionFinder
Returns the directional heading in degrees.
getDegreesCartesian() - Method in interface lejos.robotics.DirectionFinder
Compass readings increase clockwise from 0 to 360, but Cartesian coordinate systems increase counter-clockwise.
getDegreesCartesian() - Method in class lejos.robotics.DirectionFinderAdapter
 
getDegreesCartesian() - Method in class lejos.utility.GyroDirectionFinder
Returns the current rate-of-turn in degrees, as read by the GyroSensor.
getDelay() - Method in interface lejos.robotics.objectdetection.FeatureDetector
The minimum delay between notification of readings from the feature detector.
getDelay() - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
getDelay() - Method in class lejos.robotics.objectdetection.FusorDetector
 
getDelay() - Method in class lejos.utility.Timer
access how man milliseconds between timedOut() messages.
getDeviceAddress() - Method in class lejos.hardware.RemoteBTDevice
 
getDeviceClass() - Method in class lejos.hardware.RemoteBTDevice
 
getDeviceInfo() - Method in class lejos.hardware.LocalBTDevice
Return a structure providing information about the local device
getDeviceInfo() - Method in class lejos.remote.nxt.NXTCommand
Gets device information
getDeviceSignature(boolean) - Method in class lejos.hardware.device.DeviceIdentifier
return the signature of the attached device.
getDeviceType() - Method in class lejos.hardware.device.DeviceIdentifier
This method returns information on the sensor/motor that is attached to the specified port.
getDeviceType() - Method in interface lejos.hardware.port.ConfigurationPort
This function returns information on the sensor/motor that is attached to the specified port.
getDirection(int) - Method in class lejos.hardware.device.RCXMotorMultiplexer
 
getDisplacement(Move) - Method in interface lejos.robotics.chassis.Chassis
Method used by the MovePilot to update a move object that describes the move executed since the last call to startMove.
getDisplacement(Move) - Method in class lejos.robotics.chassis.WheeledChassis
 
getDisplay() - Method in interface lejos.hardware.lcd.CommonLCD
Provide access to the LCD display frame buffer.
getDisplay() - Static method in class lejos.hardware.lcd.LCD
Provide access to the LCD display frame buffer.
getDisplay() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getDisplay() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getDisplay() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
getDisplay() - Method in class lejos.remote.ev3.RemoteTextLCD
 
getDisplay() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getDisplay() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getDisplay() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
getDisplay() - Method in interface lejos.remote.ev3.RMITextLCD
 
getDistance(int) - Method in class lejos.hardware.device.SensorMux
Method used to use a US with the sensor and get the distances
getDistance(Point) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the straight line distance from this node to aPoint
getDistance(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
return the straight distance from this node to aNode
getDistanceMode() - Method in class lejos.hardware.sensor.EV3IRSensor
EV3 Infra Red sensor, Distance mode
Measures the distance to an object in front of the sensor.
getDistanceMode() - Method in class lejos.hardware.sensor.EV3UltrasonicSensor
Lego EV3 Ultrasonic sensor, Distance mode
Measures distance to an object in front of the sensor
getDistanceMode() - Method in class lejos.hardware.sensor.MindsensorsDistanceSensorV2
Returns a sample provider that measures distance (in meter).
getDistanceMode() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
Gives a SampleProvider representing the sensor in distance mode.
getDistanceTraveled() - Method in class lejos.robotics.navigation.Move
Get the distance traveled.
getDLight(int) - Method in class lejos.hardware.device.DLights
Returns the I2C driver for a single dLight.
getDoublePivot() - Method in class lejos.utility.LUDecomposition
Return pivot permutation vector as a one-dimensional double array
getElement(int) - Method in class lejos.robotics.AccelerometerAdapter
 
getElevation() - Method in class lejos.hardware.gps.Satellite
How many degrees over the horizon the satellite is.
getEmissivity() - Method in class lejos.hardware.sensor.DexterThermalIRSensor
Read the current emissivity value.
getEncoderMotor(int) - Method in class lejos.hardware.device.tetrix.TetrixMotorController
Get a TetrixEncoderMotor instance that is associated with the motorID.
getError() - Method in class lejos.remote.rcx.PacketHandler
Get the last error.
getErrorcode() - Method in exception lejos.remote.nxt.LCPException
Returns error code, if this exception was caused by the NXT returned an LCP error.
getErrorRect() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the minimum rectangle enclosing all the particles
getEstimatedPose() - Method in class lejos.robotics.localization.MCLPoseProvider
 
getEV3DumbSignature() - Method in class lejos.hardware.device.DeviceIdentifier
Returns the signature for a dumb EV3 sensor
getExecutingProgramName() - Method in interface lejos.remote.ev3.Menu
 
getExecutingProgramName() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getExecutingProgramName() - Method in interface lejos.remote.ev3.RMIMenu
 
getExternalLED() - Method in interface lejos.hardware.device.DLight
Gets the PWM value of the external LED driver of the dLight.
getExternalLED(int) - Method in class lejos.hardware.device.DLights
Gets the PWM value of the external LED driver of the dLight.
getF_Score() - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
getFactors() - Method in interface lejos.robotics.chassis.Wheel
Returns the x,y and r factors to calculate motor speed from wheel linear and angular speed.
getFactors() - Method in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
getFactors() - Method in class lejos.robotics.chassis.WheeledChassis.Modeler
 
getFileSize(String) - Method in interface lejos.remote.ev3.Menu
 
getFileSize(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getFileSize(String) - Method in interface lejos.remote.ev3.RMIMenu
 
getFirmwareVersion() - Method in class lejos.hardware.device.NXTCam
Returns the NXTCam firmware version.
getFirmwareVersion() - Method in class lejos.remote.nxt.NXJFirmwareInfo
Get the full firmware version
getFirmwareVersion() - Method in class lejos.remote.nxt.NXTCommand
Get the fimrware version.
getFixMode() - Method in class lejos.hardware.gps.SimpleGPS
Fix quality: 0 = invalid 1 = GPS fix (SPS) 2 = DGPS fix 3 = PPS fix 4 = Real Time Kinematic 5 = Float RTK 6 = estimated (dead reckoning) (2.3 feature) 7 = Manual input mode 8 = Simulation mode
getFixQuality() - Method in class lejos.hardware.gps.GGASentence
Get GPS Quality Data
getFixType() - Method in class lejos.hardware.gps.SimpleGPS
3D fix - values include: 1 = no fix 2 = 2D fix 3 = 3D fix
getFloats(float[], int, int) - Method in interface lejos.hardware.port.AnalogPort
Return a series of results obtained from the sensor.
getFloats(float[], int, int) - Method in class lejos.remote.ev3.RemoteAnalogPort
 
getFloats(float[], int, int) - Method in class lejos.remote.ev3.RemoteRequestAnalogPort
 
getFloats(float[], int, int) - Method in interface lejos.remote.ev3.RMIAnalogPort
 
getFloats(float[], int, int) - Method in class lejos.remote.ev3.RMIRemoteAnalogPort
 
getFloats(float[], int, int) - Method in class lejos.remote.nxt.RemoteNXTAnalogPort
 
getFloodlight() - Method in class lejos.hardware.sensor.EV3ColorSensor
Returns the color of the floodlight, including Color.NONE.
getFloodlight() - Method in class lejos.hardware.sensor.NXTColorSensor
 
getFloodlight() - Method in class lejos.hardware.sensor.NXTLightSensor
 
getFloodlight() - Method in class lejos.hardware.sensor.RCXLightSensor
 
getFloodlight() - Method in interface lejos.robotics.LampController
Returns the color of the floodlight, including Color.NONE.
getFont(int, int, int) - Static method in class lejos.hardware.lcd.Font
Request a particular type and size of font.
getFont() - Method in interface lejos.hardware.lcd.GraphicsLCD
Return the currently selected font object.
getFont() - Method in interface lejos.hardware.lcd.TextLCD
Get the current font
getFont() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getFont() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getFont() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
getFont() - Method in class lejos.remote.ev3.RemoteTextLCD
 
getFont() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getFont() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getFont() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
getFont() - Method in interface lejos.remote.ev3.RMITextLCD
 
getForward() - Method in class lejos.robotics.chassis.WheeledChassis
 
getFrame() - Method in class lejos.robotics.geometry.RectangularShape
Get the framing rectangle
getFreeThreshold() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getFrequency() - Method in class lejos.robotics.filter.PublishedSource
 
getFriendlyName() - Method in class lejos.hardware.LocalBTDevice
Return the name of the local device
getFriendlyName() - Method in class lejos.remote.nxt.NXTCommand
Get the friendly name of the NXT
getG_Score() - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
getGain() - Method in class lejos.utility.KalmanFilter
 
getGraphics() - Method in class lejos.hardware.lcd.Image
Returns a graphics object that can be used to draw to the image.
getGraphicsLCD() - Method in interface lejos.hardware.Brick
Get graphics access to the LCD
getGraphicsLCD() - Method in class lejos.hardware.ev3.LocalEV3
 
getGraphicsLCD() - Method in class lejos.remote.ev3.RemoteEV3
 
getGraphicsLCD() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getGraphicsLCD() - Method in interface lejos.remote.ev3.RMIEV3
 
getGraphicsLCD() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getGraphicsLCD() - Method in class lejos.remote.nxt.RemoteNXT
 
getGreen() - Method in class lejos.robotics.Color
Returns the green component in the range 0-255 in the default sRGB space.
getGreenMode() - Method in class lejos.hardware.sensor.NXTColorSensor
get a sample provider the returns the light value when illuminated with a Green light source.
getHDOP() - Method in class lejos.hardware.gps.GGASentence
Get Horizontal Dilution of Precision (HDOP)
getHDOP() - Method in class lejos.hardware.gps.GSASentence
Return HDOP
getHDOP() - Method in class lejos.hardware.gps.SimpleGPS
Get the Horizontal Dilution of Precision (HDOP).
getHeader() - Method in class lejos.hardware.gps.GGASentence
Returns the NMEA header for this sentence.
getHeader() - Method in class lejos.hardware.gps.GSASentence
Returns the NMEA header for this sentence.
getHeader() - Method in class lejos.hardware.gps.GSVSentence
Returns the NMEA header for this sentence.
getHeader() - Method in class lejos.hardware.gps.NMEASentence
Retrieve the header constant for this sentence.
getHeader() - Method in class lejos.hardware.gps.RMCSentence
Returns the NMEA header for this sentence.
getHeader() - Method in class lejos.hardware.gps.VTGSentence
Returns the NMEA header for this sentence.
getHeading(float, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Given the former heading and the change in heading, this method will calculate a new heading.
getHeading(Point, Point) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Calculates the heading designated by two points.
getHeading() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Returns direction of desired robot facing
getHeading() - Method in class lejos.robotics.navigation.Pose
returns the heading (direction angle) of the Pose
getHeading() - Method in class lejos.robotics.navigation.Waypoint
 
getHeadingError() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Determines the difference between actual compass direction and desired heading in degrees
getHeight() - Method in interface lejos.hardware.lcd.CommonLCD
Return the height of the associated drawing surface.
getHeight() - Method in class lejos.hardware.lcd.Font
return the height of the font in pixels.
getHeight() - Method in class lejos.hardware.lcd.Image
return the height of the image.
getHeight() - Method in interface lejos.hardware.video.Video
return the frame height
getHeight() - Method in class lejos.hardware.video.YUYVImage
return the image height
getHeight() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getHeight() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getHeight() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
getHeight() - Method in class lejos.remote.ev3.RemoteTextLCD
 
getHeight() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getHeight() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getHeight() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
getHeight() - Method in interface lejos.remote.ev3.RMITextLCD
 
getHeight() - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
getHeight() - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
getHeight() - Method in class lejos.robotics.geometry.RectangleInt32
Get the height as a double
getHeight() - Method in class lejos.robotics.geometry.RectangularShape
Get the height as a double
getHeight() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getHigh() - Method in interface lejos.robotics.LightDetector
The highest raw light value this sensor can return from intense bright light.
getHigh() - Method in class lejos.robotics.LightDetectorAdaptor
 
getHost() - Method in class lejos.remote.ev3.RemoteEV3
 
getHost() - Method in class lejos.robotics.filter.PublishedSource
 
getHost() - Method in class lejos.robotics.filter.SubscribedProvider
 
getHour() - Method in interface lejos.robotics.Clock
 
getHWDisplay() - Method in interface lejos.hardware.lcd.CommonLCD
Get access to hardware LCD display.
getHWDisplay() - Static method in class lejos.hardware.lcd.LCD
 
getHWDisplay() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getHWDisplay() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getHWDisplay() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
getHWDisplay() - Method in class lejos.remote.ev3.RemoteTextLCD
 
getHWDisplay() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getHWDisplay() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getHWDisplay() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
getHWDisplay() - Method in interface lejos.remote.ev3.RMITextLCD
 
getI2CSignature(boolean) - Method in class lejos.hardware.device.DeviceIdentifier
Returns the signature for a i2c sensor
getId() - Method in interface lejos.hardware.Key
 
getId() - Method in class lejos.remote.ev3.RemoteKey
 
getId() - Method in class lejos.remote.ev3.RemoteRequestKey
 
getId() - Method in interface lejos.remote.ev3.RMIKey
 
getId() - Method in class lejos.remote.ev3.RMIRemoteKey
 
getIfNames() - Static method in class lejos.hardware.Wifi
 
getInputStream() - Method in class lejos.hardware.device.UART
Return the InputStream associated with this device.
getInputStream() - Method in class lejos.remote.rcx.RCXAbstractPort
Returns an input stream for this RCXPort.
getInputValues(int) - Method in class lejos.remote.nxt.NXTCommand
Get input values for a specific NXT sensor port
getInstance(int) - Method in class lejos.hardware.device.TouchMUX
Return a Touch interface providing access to the sensor specified by the given id.
getIPAddress() - Method in class lejos.hardware.BrickInfo
 
getIpAddress() - Method in class lejos.robotics.filter.PublishedSource
 
getItems() - Method in class lejos.utility.TextMenu
Returns list of items in this menu;
getIterationCount() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
getIterationCount() - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
getIterations() - Method in class lejos.robotics.localization.MCLParticleSet
 
getKey(String) - Method in interface lejos.hardware.Brick
Get access to a specific Key (aka Button)
getKey(String) - Method in class lejos.hardware.ev3.LocalEV3
 
getKey(String) - Method in class lejos.remote.ev3.RemoteEV3
 
getKey(String) - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getKey(String) - Method in interface lejos.remote.ev3.RMIEV3
 
getKey(String) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getKey(String) - Method in class lejos.remote.nxt.RemoteNXT
 
getKey() - Method in class lejos.robotics.filter.PublishedSource
 
getKeyClickLength() - Static method in class lejos.hardware.Button
Return the current key click length.
getKeyClickLength() - Method in interface lejos.hardware.Keys
 
getKeyClickLength() - Method in class lejos.remote.ev3.RemoteKeys
 
getKeyClickLength() - Method in class lejos.remote.ev3.RemoteRequestKeys
 
getKeyClickLength() - Method in interface lejos.remote.ev3.RMIKeys
 
getKeyClickLength() - Method in class lejos.remote.ev3.RMIRemoteKeys
 
getKeyClickTone(int) - Static method in class lejos.hardware.Button
Return the click freq for a particular key.
getKeyClickTone(int) - Method in interface lejos.hardware.Keys
 
getKeyClickTone(int) - Method in class lejos.remote.ev3.RemoteKeys
 
getKeyClickTone(int) - Method in class lejos.remote.ev3.RemoteRequestKeys
 
getKeyClickTone(int) - Method in interface lejos.remote.ev3.RMIKeys
 
getKeyClickTone(int) - Method in class lejos.remote.ev3.RMIRemoteKeys
 
getKeyClickVolume() - Static method in class lejos.hardware.Button
Return the current key click volume.
getKeyClickVolume() - Method in interface lejos.hardware.Keys
 
getKeyClickVolume() - Method in class lejos.remote.ev3.RemoteKeys
 
getKeyClickVolume() - Method in class lejos.remote.ev3.RemoteRequestKeys
 
getKeyClickVolume() - Method in interface lejos.remote.ev3.RMIKeys
 
getKeyClickVolume() - Method in class lejos.remote.ev3.RMIRemoteKeys
 
getKeyClickVolume() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to get the master volume level
getKeys() - Method in interface lejos.hardware.Brick
Get access to the keys (buttons)
getKeys() - Method in class lejos.hardware.ev3.LocalEV3
 
getKeys() - Method in class lejos.remote.ev3.RemoteEV3
 
getKeys() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getKeys() - Method in interface lejos.remote.ev3.RMIEV3
 
getKeys() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getKeys() - Method in class lejos.remote.nxt.RemoteNXT
 
getL() - Method in class lejos.utility.LUDecomposition
Return lower triangular factor
getLargeFont() - Static method in class lejos.hardware.lcd.Font
Return the large font.
getLargestIndex(ArrayList<Double>) - Static method in class lejos.robotics.localization.BeaconPoseProvider
 
getLaserMode() - Method in class lejos.hardware.sensor.DexterLaserSensor
Dexter laser sensor, Laser mode
Measures light level with the laser on
getLatitude() - Method in class lejos.hardware.gps.Coordinates
Returns the latitude component of this coordinate.
getLatitude() - Method in class lejos.hardware.gps.GGASentence
Get Latitude
getLatitude() - Method in class lejos.hardware.gps.RMCSentence
Get Latitude
getLatitude() - Method in class lejos.hardware.gps.SimpleGPS
Get Latitude
getLatitudeDirection() - Method in class lejos.hardware.gps.GGASentence
Get Latitude Direction
getLatitudeDirection() - Method in class lejos.hardware.gps.SimpleGPS
Get Latitude Direction
getLED() - Method in interface lejos.hardware.Brick
Get access to the LED
getLED() - Method in class lejos.hardware.ev3.LocalEV3
 
getLED() - Method in class lejos.remote.ev3.RemoteEV3
 
getLED() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getLED() - Method in interface lejos.remote.ev3.RMIEV3
 
getLED() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getLED() - Method in class lejos.remote.nxt.RemoteNXT
 
getLeftX() - Method in class lejos.hardware.device.PSPNXController
 
getLeftY() - Method in class lejos.hardware.device.PSPNXController
 
getLightValue() - Method in interface lejos.robotics.LightDetector
Returns the calibrated and normalized brightness of the white light detected.
getLightValue() - Method in class lejos.robotics.LightDetectorAdaptor
returns the raw light value using whatever mode has been set.
getLimitAngle() - Method in class lejos.hardware.device.MMXRegulatedMotor
Return the angle that this Motor is rotating to or last rotated to.
getLimitAngle() - Method in class lejos.hardware.device.tetrix.TetrixEncoderMotor
Return the last angle that this motor was rotating to via one of the rotate methods.
getLimitAngle() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Return the angle that this Motor is rotating to.
getLimitAngle() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
getLimitAngle() - Method in interface lejos.hardware.motor.MotorRegulator
Return the angle that this Motor is rotating to.
getLimitAngle() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
getLimitAngle() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Return the limit angle (if any)
getLimitAngle() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
getLimitAngle() - Method in class lejos.robotics.MirrorMotor
 
getLimitAngle() - Method in interface lejos.robotics.RegulatedMotor
Return the limit angle (if any)
getLinearAcceleration() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getLinearAcceleration() - Method in interface lejos.robotics.chassis.Chassis
Gets the setting for linear acceleration as is used in travel, arc, rotate and setvelocity methods
getLinearAcceleration() - Method in class lejos.robotics.chassis.WheeledChassis
 
getLinearAcceleration() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getLinearAcceleration() - Method in interface lejos.robotics.navigation.MoveController
Returns the acceleration at which the robot accelerates at the start of a move and decelerates at the end of a move.
getLinearAcceleration() - Method in class lejos.robotics.navigation.MovePilot
 
getLinearAcceleration() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getLinearAcceleration() - Method in class lejos.robotics.navigation.SteeringPilot
 
getLinearDirection() - Method in interface lejos.robotics.chassis.Chassis
Returns the current direction of the linear speed component of the robot
getLinearDirection() - Method in class lejos.robotics.chassis.WheeledChassis
 
getLinearSpeed() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getLinearSpeed() - Method in interface lejos.robotics.chassis.Chassis
Gets the setting for linear speed as is used in moveTo, Arc, and Rotate methods
getLinearSpeed() - Method in class lejos.robotics.chassis.WheeledChassis
 
getLinearSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getLinearSpeed() - Method in interface lejos.robotics.navigation.MoveController
Returns the speed at which the robot will travel forward and backward (and to some extent arcs, although actual arc speed is slightly less).
getLinearSpeed() - Method in class lejos.robotics.navigation.MovePilot
 
getLinearSpeed() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getLinearSpeed() - Method in class lejos.robotics.navigation.SteeringPilot
 
getLinearVelocity() - Method in interface lejos.robotics.chassis.Chassis
Returns the linear component of the current speed of the robot
getLinearVelocity() - Method in class lejos.robotics.chassis.WheeledChassis
 
getLines() - Method in class lejos.robotics.mapping.LineMap
Get the lines as an array
getLink() - Static method in class lejos.remote.rcx.LLC
Return the RCXLink object associated with LLC
getLink() - Static method in class lejos.remote.rcx.Serial
Get the RCXLink object associated with the Serial class
getListenMode() - Method in class lejos.hardware.sensor.EV3UltrasonicSensor
Lego EV3 Ultrasonic sensor, Listen mode
Listens for the presence of other ultrasonic sensors.
getLocal() - Static method in class lejos.hardware.BrickFinder
 
getLocalAddress() - Method in class lejos.remote.nxt.NXTCommand
Get the local address of the NXT.
getLocalDevice() - Static method in class lejos.hardware.Bluetooth
 
getLocalDevice(String) - Static method in class lejos.hardware.Wifi
 
getLocalVersion() - Method in class lejos.hardware.LocalBTDevice
return a structure providing local version information
getLocation() - Method in class lejos.robotics.geometry.RectangleInt32
Get the location of the rectangle
getLocation() - Method in class lejos.robotics.navigation.Pose
Get the location as a Point
getLocation() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
return the location of this node
getLongDistanceMode() - Method in class lejos.hardware.sensor.HiTechnicEOPD
HiTechnic EOPD sensor, Long distance mode
Measures the relative distance to a surface.
getLongitude() - Method in class lejos.hardware.gps.Coordinates
Returns the longitude component of this coordinate.
getLongitude() - Method in class lejos.hardware.gps.GGASentence
Get Longitude
getLongitude() - Method in class lejos.hardware.gps.RMCSentence
Get Longitude
getLongitude() - Method in class lejos.hardware.gps.SimpleGPS
Get Longitude
getLongitudeDirection() - Method in class lejos.hardware.gps.GGASentence
Get Longitude Direction
getLongitudeDirection() - Method in class lejos.hardware.gps.SimpleGPS
Get Longitude Direction
getLow() - Method in interface lejos.robotics.LightDetector
The lowest raw light value this sensor can return in pitch black darkness.
getLow() - Method in class lejos.robotics.LightDetectorAdaptor
 
getLSC(int) - Method in class lejos.hardware.device.NXTe
Get a LSC, Lattebox Servo Controller
getMagneticMode() - Method in class lejos.hardware.sensor.DexterCompassSensor
Dexter Industries dCompass sensor, magnetic mode
Measures the strength of the magnetic field over three axes
getMagneticMode() - Method in class lejos.hardware.sensor.HiTechnicMagneticSensor
HiTechnic Magnetic sensor, Magnetic mode
Measures the strength og the vertical magnetic field
getMagneticMode() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Return a SensorMode object that will return Magnetic data for the X, Y and Z axis The data is returned in Guass
getMap() - Method in class lejos.robotics.mapping.NavigationModel
Get the registered map
getMap() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
getMap() - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
getMatrix(int, int, int, int) - Method in class lejos.utility.Matrix
Get a submatrix.
getMatrix(int[], int[]) - Method in class lejos.utility.Matrix
Get a submatrix.
getMatrix(int, int, int[]) - Method in class lejos.utility.Matrix
Get a submatrix.
getMatrix(int[], int, int) - Method in class lejos.utility.Matrix
Get a submatrix.
getMax(Matrix) - Method in class lejos.robotics.chassis.WheeledChassis
Gets the biggest value from a matrix
getMaxAngularSpeed() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getMaxAngularSpeed() - Method in interface lejos.robotics.chassis.Chassis
Returns how fast the robot can rotate.
getMaxAngularSpeed() - Method in class lejos.robotics.chassis.WheeledChassis
 
getMaxAngularSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getMaxAngularSpeed() - Method in class lejos.robotics.navigation.MovePilot
 
getMaxAngularSpeed() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getMaxAngularSpeed() - Method in interface lejos.robotics.navigation.RotateMoveController
returns the maximum value of the rotation speed;
getMaxDistance() - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
Returns the maximum distance the FeatureDetector will return for detected objects.
getMaxHeadingError() - Method in class lejos.robotics.navigation.Waypoint
 
getMaximumRange() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
getMaxLinearSpeed() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getMaxLinearSpeed() - Method in interface lejos.robotics.chassis.Chassis
Returns the maximum speed of the robot.
getMaxLinearSpeed() - Method in class lejos.robotics.chassis.WheeledChassis
 
getMaxLinearSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getMaxLinearSpeed() - Method in interface lejos.robotics.navigation.MoveController
Returns the maximum speed at which this robot is capable of traveling forward and backward.
getMaxLinearSpeed() - Method in class lejos.robotics.navigation.MovePilot
 
getMaxLinearSpeed() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getMaxLinearSpeed() - Method in class lejos.robotics.navigation.SteeringPilot
 
getMaxPositionError() - Method in class lejos.robotics.navigation.Waypoint
 
getMaxRotateSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getMaxSpeed() - Method in class lejos.hardware.device.MMXRegulatedMotor
 
getMaxSpeed() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
NOT IMPLEMENTED as the TEXTRIX motor controller does not support this command.
getMaxSpeed() - Method in class lejos.hardware.motor.BaseRegulatedMotor
 
getMaxSpeed() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
getMaxSpeed() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Returns the maximim speed of the motor.
getMaxSpeed() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
getMaxSpeed() - Method in class lejos.robotics.MirrorMotor
 
getMaxSpeed() - Method in interface lejos.robotics.RegulatedMotor
Returns the maximum speed that can be maintained by the regulation system based upon the current state of the battery.
getMaxWeight() - Method in class lejos.robotics.localization.MCLParticleSet
The highest weight of any particle
getMaxX() - Method in class lejos.robotics.geometry.RectangularShape
Get the maximum value of the x coordinate
getMaxX() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the maximum value of X in the particle set
getMaxY() - Method in class lejos.robotics.geometry.RectangularShape
Get the maximum value of the y coordinate
getMaxY() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the maximum value of Y in the particle set;
getMean() - Method in class lejos.robotics.filter.OffsetCorrectionFilter
Returns the mean sample value
getMean() - Method in class lejos.utility.KalmanFilter
 
getMeanY() - Method in class lejos.hardware.video.YUYVImage
Return the mean of the Y components for the image (mean brightness)
getMeasurementMode() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
getMenuVersion() - Method in interface lejos.remote.ev3.Menu
 
getMenuVersion() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getMenuVersion() - Method in interface lejos.remote.ev3.RMIMenu
 
getMenuVersion() - Method in class lejos.remote.nxt.NXJFirmwareInfo
Get the full firmware version
getMesh() - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
getMesh() - Method in interface lejos.robotics.pathfinding.NavigationMesh
Returns a collection of all nodes within this navigation mesh.
getMinRadius() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getMinRadius() - Method in interface lejos.robotics.chassis.Chassis
Returns the smallest possible radius this chassis is able turn
getMinRadius() - Method in class lejos.robotics.chassis.WheeledChassis
 
getMinRadius() - Method in interface lejos.robotics.navigation.ArcMoveController
The minimum steering radius this vehicle is capable of when traveling in an arc.
getMinRadius() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getMinRadius() - Method in class lejos.robotics.navigation.MovePilot
 
getMinRadius() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getMinRadius() - Method in class lejos.robotics.navigation.SteeringPilot
In practice, a robot might steer tighter with one turn than the other.
getMinute() - Method in interface lejos.robotics.Clock
 
getMinX() - Method in class lejos.robotics.geometry.RectangularShape
Get the minimum value of the x x coordinate
getMinX() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the minimum value of X in the particle set;
getMinY() - Method in class lejos.robotics.geometry.RectangularShape
Get the minimum value of the y coordinate
getMinY() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the minimum value of Y in the particle set;
getMode() - Method in class lejos.hardware.device.PSPNXController
Returns the current operating mode of the sensor.
getMode() - Method in class lejos.hardware.gps.GSASentence
Return Mode1.
getMode() - Method in interface lejos.hardware.port.BasicSensorPort
Get the current operating mode of the sensor
getMode(int) - Method in class lejos.hardware.sensor.BaseSensor
 
getMode(String) - Method in class lejos.hardware.sensor.BaseSensor
 
getMode(int) - Method in interface lejos.hardware.sensor.SensorModes
Return the sample provider interface for the requested mode
getMode(String) - Method in interface lejos.hardware.sensor.SensorModes
Return the sample provider for the request mode
getMode() - Method in class lejos.remote.ev3.RemoteIOPort
 
getMode() - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
getMode() - Method in class lejos.remote.nxt.RemoteNXTIOPort
Get the current operating mode of the sensor
getMode() - Method in class lejos.robotics.LightDetectorAdaptor
 
getModeCount() - Method in class lejos.hardware.sensor.BaseSensor
 
getModeCount() - Method in interface lejos.hardware.sensor.SensorModes
Gets the number of supported modes
getModeName(int) - Method in interface lejos.hardware.port.UARTPort
Get the string name of the specified mode.
getModeName(int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
getModeName(int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
getModeName(int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
getModeName(int) - Method in interface lejos.remote.ev3.RMIUARTPort
Get the string name of the specified mode.
getModeValue() - Method in class lejos.hardware.gps.GSASentence
Return Mode2.
getModulatedMode() - Method in class lejos.hardware.sensor.HiTechnicIRSeekerV2
HiTechnic IR seeker V2, modulated mode
Measures the angle to a source of a modulated infrared light.
getMonth() - Method in interface lejos.robotics.Clock
 
getMotor() - Method in class lejos.hardware.device.PFMate
Returns which motors are activated
getMotor() - Method in interface lejos.robotics.chassis.Wheel
 
getMotor() - Method in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
getMotor() - Method in class lejos.robotics.chassis.WheeledChassis.Modeler
 
getMotor() - Method in class lejos.robotics.LightScanner
 
getMotor(String) - Static method in class lejos.utility.PilotProps
Utility method to get Motor instance from string (A, B or C)
getMotorCurrent() - Static method in class lejos.hardware.Battery
 
getMotorCurrent() - Method in interface lejos.hardware.Power
return the motor current draw
getMotorCurrent() - Method in class lejos.remote.ev3.RemoteBattery
 
getMotorCurrent() - Method in class lejos.remote.ev3.RemoteRequestBattery
 
getMotorCurrent() - Method in interface lejos.remote.ev3.RMIBattery
return the motor current draw
getMotorCurrent() - Method in class lejos.remote.ev3.RMIRemoteBattery
 
getMotorCurrent() - Method in class lejos.remote.nxt.RemoteNXTBattery
 
getMotorSignature() - Method in class lejos.hardware.device.DeviceIdentifier
Returns the signature for a motor/output device
getMoveController() - Method in class lejos.robotics.navigation.Navigator
Returns the MoveController belonging to this object.
getMoveDirection() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Gets the move direction.
getMovement() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
getMovement() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getMovement() - Method in class lejos.robotics.navigation.MovePilot
 
getMovement() - Method in interface lejos.robotics.navigation.MoveProvider
Returns the move made since the move started, but before it has completed.
getMovement() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
getMovement() - Method in class lejos.robotics.navigation.SteeringPilot
 
getMovementIncrement() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
getMovementIncrement() - Method in class lejos.robotics.navigation.SteeringPilot
 
getMoveType() - Method in class lejos.robotics.navigation.Move
Get the type of the movement performed
getName() - Method in interface lejos.hardware.Brick
Get he name of the brick
getName() - Method in class lejos.hardware.BrickInfo
 
getName() - Method in class lejos.hardware.device.LMotor
Get name from a RC Servo or a DC Motor
getName() - Method in class lejos.hardware.device.PFMotorPort
 
getName() - Method in class lejos.hardware.device.RCXPlexedMotorPort
 
getName() - Method in class lejos.hardware.ev3.LocalEV3
 
getName() - Method in interface lejos.hardware.Key
 
getName() - Method in interface lejos.hardware.port.IOPort
Return the string representing this port
getName() - Method in interface lejos.hardware.port.Port
return the string name used to reference this physical port
getName() - Method in class lejos.hardware.RemoteBTDevice
 
getName() - Method in class lejos.hardware.sensor.BaseSensor
 
getName() - Method in class lejos.hardware.sensor.DexterIMUSensor.DexterIMUAccelerationSensor
 
getName() - Method in class lejos.hardware.sensor.HiTechnicColorSensor.RGBMode
 
getName() - Method in class lejos.hardware.sensor.HiTechnicEOPD.ShortDistanceMode
 
getName() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
getName() - Method in class lejos.hardware.sensor.NXTSoundSensor.DBMode
 
getName() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor.DistanceMode
 
getName() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor.PingMode
 
getName() - Method in interface lejos.hardware.sensor.SensorMode
return a string description of this sensor mode
getName() - Method in interface lejos.remote.ev3.Menu
 
getName() - Method in class lejos.remote.ev3.RemoteEV3
 
getName() - Method in class lejos.remote.ev3.RemoteIOPort
 
getName() - Method in class lejos.remote.ev3.RemoteKey
 
getName() - Method in class lejos.remote.ev3.RemotePort
return the string name used to reference this physical port
getName() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getName() - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
getName() - Method in class lejos.remote.ev3.RemoteRequestKey
 
getName() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getName() - Method in class lejos.remote.ev3.RemoteRequestPort
 
getName() - Method in interface lejos.remote.ev3.RMIEV3
 
getName() - Method in interface lejos.remote.ev3.RMIMenu
 
getName() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getName() - Static method in class lejos.remote.nxt.NXTCommDevice
Return the current USB devName.
getName() - Method in class lejos.remote.nxt.RemoteNXT
 
getName() - Method in class lejos.remote.nxt.RemoteNXTIOPort
Return the string representing this port
getName() - Method in class lejos.remote.nxt.RemoteNXTPort
return the string name used to reference this physical port
getName() - Method in class lejos.remote.rcx.RCXRemoteMotorPort
 
getName() - Method in class lejos.robotics.filter.PublishedSource
 
getName() - Method in class lejos.robotics.filter.SubscribedProvider
 
getNeighbors() - Method in class lejos.robotics.pathfinding.Node
Returns all the neighbors which this node is connected to.
getNeighbors() - Method in class lejos.robotics.pathfinding.RandomSelfGeneratingNode
When this method is called the first time, it randomly generates a set of neighbors according to the parameters in the constructor.
getNodeCount() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
getNodeCount() - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
getNormalized() - Method in class lejos.robotics.geometry.Point
get a copy of this with length 1
getNormalizedLightValue() - Method in interface lejos.robotics.LightDetector
Returns the normalized value of the brightness of the white light detected, such that the lowest value is darkness and the highest value is intense bright light.
getNormalizedLightValue() - Method in class lejos.robotics.LightDetectorAdaptor
call setHigh() and setLow() before using this method.
getNumberOfObjects() - Method in class lejos.hardware.device.NXTCam
Get the number of objects being tracked
getNumPixels() - Method in class lejos.hardware.video.YUYVImage
return the number of pixels in the image
getNumReadings() - Method in class lejos.robotics.RangeReadings
Get the number of readings in a set
getNXJFirmwareInfo() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to get the NXJ firmware and menu information
getNXJFirmwareVersion() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to get the NXJ firmware version
getNXJMenuVersion() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to get the NXJ start-up menu version
getNXTCommand() - Method in class lejos.remote.nxt.RemoteNXT
 
getNXTCommConnector() - Static method in class lejos.hardware.Bluetooth
 
getNXTDumbSignature() - Method in class lejos.hardware.device.DeviceIdentifier
Returns the signature for a dumb NXT sensor
getObjectColor(int) - Method in class lejos.hardware.device.NXTCam
Get the color number for a tracked object
getObjectMode() - Method in class lejos.hardware.sensor.DexterThermalIRSensor
Dexter Industries Thermal Infrared Sensor, Object mode
Measures the temperature of an objects surface
getObstacle() - Method in class lejos.hardware.sensor.SumoEyesSensor
Returns the detected zone (NO_DETECTION (0) , RIGHT (1), CENTER (2), LEFT (3))
getOccupied(int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getOccupiedThreshold() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getOffsetCorrection() - Method in class lejos.robotics.filter.LinearCalibrationFilter
Returns an array with the offset correction parameters that are currently in use
getOldest(float[], int) - Method in class lejos.robotics.filter.SampleBuffer
 
getOperatingMode() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
getOutputState(int) - Method in class lejos.remote.nxt.NXTCommand
Retrieves the current output state for a port.
getOutputStream() - Method in class lejos.hardware.device.UART
Return the OutputStream associated with this device.
getOutputStream() - Method in class lejos.remote.rcx.RCXAbstractPort
Returns an output stream for this RCXPort.
getP1() - Method in class lejos.robotics.geometry.Line
 
getP1() - Method in class lejos.robotics.geometry.Line2D.Double
 
getP1() - Method in class lejos.robotics.geometry.Line2D.Float
 
getP1() - Method in class lejos.robotics.geometry.Line2D
Get the start point of the line as a Point2D
getP2() - Method in class lejos.robotics.geometry.Line
 
getP2() - Method in class lejos.robotics.geometry.Line2D.Double
 
getP2() - Method in class lejos.robotics.geometry.Line2D.Float
 
getP2() - Method in class lejos.robotics.geometry.Line2D
Get the end point of the line as a Point2D
getPairedDevices() - Method in class lejos.hardware.LocalBTDevice
Return a list of the devices we are paired with
getParticle(int) - Method in class lejos.robotics.localization.MCLParticleSet
Get a specific particle
getParticles() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the particle set
getParticles() - Method in class lejos.robotics.mapping.NavigationModel
Get the registered particle set
getPath() - Method in class lejos.robotics.mapping.NavigationModel
Get the registered path
getPath() - Method in class lejos.robotics.navigation.Navigator
Gets the current path
getPDOP() - Method in class lejos.hardware.gps.GSASentence
Return PDOP
getPDOP() - Method in class lejos.hardware.gps.SimpleGPS
Get the 3D Position Dilution of Precision (PDOP).
getPhase() - Method in class lejos.hardware.sensor.RCXRotationSensor
Returns the current phase of the sensor.
getPin1() - Method in interface lejos.hardware.port.AnalogPort
return the voltage present on pin 1 of the sensor port
getPin1() - Method in class lejos.remote.ev3.RemoteAnalogPort
 
getPin1() - Method in class lejos.remote.ev3.RemoteRequestAnalogPort
 
getPin1() - Method in interface lejos.remote.ev3.RMIAnalogPort
 
getPin1() - Method in class lejos.remote.ev3.RMIRemoteAnalogPort
 
getPin1() - Method in class lejos.remote.nxt.RemoteNXTAnalogPort
 
getPin6() - Method in interface lejos.hardware.port.AnalogPort
return the voltage present on pin 6 of the sensor port
getPin6() - Method in class lejos.remote.ev3.RemoteAnalogPort
 
getPin6() - Method in class lejos.remote.ev3.RemoteRequestAnalogPort
 
getPin6() - Method in interface lejos.remote.ev3.RMIAnalogPort
 
getPin6() - Method in class lejos.remote.ev3.RMIRemoteAnalogPort
 
getPin6() - Method in class lejos.remote.nxt.RemoteNXTAnalogPort
 
getPingMode() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
Gives a SampleProvider representing the sensor in ping mode.
getPivot() - Method in class lejos.utility.LUDecomposition
Return pivot permutation vector
getPixel(int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Method to get a pixel from the screen.
getPixel(int, int) - Static method in class lejos.hardware.lcd.LCD
Method to get a pixel from the screen.
getPixel(int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getPixel(int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getPixel(int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getPixel(int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getPort(String) - Method in interface lejos.hardware.Brick
Return a port object for the request port name.
getPort(String) - Method in class lejos.hardware.ev3.LocalEV3
Return a port object for the request port name.
getPort() - Method in class lejos.hardware.sensor.I2CSensor
Get the port that the sensor is attached to
getPort(String) - Method in class lejos.remote.ev3.RemoteEV3
 
getPort(String) - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getPort(String) - Method in class lejos.remote.nxt.RemoteNXT
 
getPort() - Method in class lejos.robotics.filter.PublishedSource
 
getPortType() - Method in class lejos.hardware.device.DeviceIdentifier
Get the type classification for the port.
getPortType() - Method in interface lejos.hardware.port.ConfigurationPort
Get the type classification for the port.
getPortType(int) - Static method in class lejos.remote.nxt.RemoteNXTAnalogPort
get the type of the port
getPose() - Method in class lejos.robotics.localization.BeaconPoseProvider
 
getPose() - Method in class lejos.robotics.localization.CompassPoseProvider
 
getPose() - Method in class lejos.robotics.localization.MCLParticle
Return the pose of this particle
getPose() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the best best estimate of the current pose;
getPose() - Method in class lejos.robotics.localization.OdometryPoseProvider
returns a new pose that represents the current location and heading of the robot.
getPose() - Method in interface lejos.robotics.localization.PoseProvider
 
getPose() - Method in class lejos.robotics.navigation.Waypoint
Return a Pose that represents the way point.
getPose() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getPoseProvider() - Method in interface lejos.robotics.chassis.Chassis
Returns an Pose provider that uses odometry to keep track of the pose of the chassis
getPoseProvider() - Method in class lejos.robotics.chassis.WheeledChassis
 
getPoseProvider() - Method in class lejos.robotics.navigation.Navigator
Returns the PoseProvider
getPosition() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Returns the current position that the motor regulator is trying to maintain.
getPosition() - Method in class lejos.hardware.motor.JavaMotorRegulator
return the regulations models current position.
getPosition() - Method in interface lejos.hardware.motor.MotorRegulator
return the regulations models current position.
getPositionMode() - Method in class lejos.hardware.sensor.DexterGPSSensor
Dexter dGPS sensor, Position mode
Gets the coordinates of the sensor
getPower() - Method in interface lejos.hardware.Brick
return a battery object which can be used to obtain battery voltage etc.
getPower() - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Returns the current actuator motor power setting.
getPower() - Method in class lejos.hardware.device.MMXMotor
 
getPower() - Method in class lejos.hardware.device.PFMateMotor
 
getPower() - Method in class lejos.hardware.device.tetrix.TetrixMotor
 
getPower() - Method in class lejos.hardware.ev3.LocalEV3
return a battery object which can be used to obtain battery voltage etc.
getPower() - Method in class lejos.hardware.motor.BasicMotor
 
getPower() - Method in class lejos.remote.ev3.RemoteEV3
 
getPower() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getPower() - Method in class lejos.remote.nxt.RemoteNXT
 
getPower() - Method in interface lejos.robotics.DCMotor
Returns the current motor power setting.
getPower() - Method in interface lejos.robotics.LinearActuator
Returns the current actuator motor power setting.
getPredecessor() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the predecessor of this node in the shortest path from the start
getPredecessor() - Method in class lejos.robotics.pathfinding.Node
Used by A* search.
getPredictedCovariance() - Method in class lejos.utility.KalmanFilter
 
getPredictedMean() - Method in class lejos.utility.KalmanFilter
 
getPressure() - Method in interface lejos.robotics.PressureDetector
Get the pressure reading in kilopascals
getPressureMode() - Method in class lejos.hardware.sensor.DexterPressureSensor250
Dexter Industries DPressure250, Pressure mode
Measures the pressure
getPressureMode() - Method in class lejos.hardware.sensor.DexterPressureSensor500
Dexter Industries DPressure500, Pressure mode
Measures the pressure
getPressureMode() - Method in class lejos.hardware.sensor.HiTechnicBarometer
HiTechnic Barometer, Pressure mode
Measures the atmospheric pressure of the air.
getPressureMode() - Method in class lejos.hardware.sensor.MindSensorsPressureSensor
Return a ample provider for pressure mode.
getPRN() - Method in class lejos.hardware.gps.GSASentence
Return an Array with Satellite IDs
getPRN() - Method in class lejos.hardware.gps.Satellite
Return PRN number from a Satellite.
getPRN() - Method in class lejos.hardware.gps.SimpleGPS
Get an Array of Pseudo-Random Noise codes (PRN).
getProductID() - Method in class lejos.hardware.sensor.DexterThermalIRSensor
 
getProductID() - Method in class lejos.hardware.sensor.I2CSensor
Read the sensor's product identifier.
getProgramNames() - Method in interface lejos.remote.ev3.Menu
 
getProgramNames() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getProgramNames() - Method in interface lejos.remote.ev3.RMIMenu
 
getProperty(String) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
 
getPropertyArray(String) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
 
getPulse() - Method in class lejos.hardware.device.LMotor
This method return current pulse over a RC Servo or a DC Motor.
getPulse() - Method in class lejos.hardware.device.MServo
Return the pulse used in last operation
getpulseWidth() - Method in class lejos.hardware.device.tetrix.TetrixServo
 
getpulseWidth() - Method in interface lejos.robotics.Servo
Get the current PWM pulse width for the servo.
getRange() - Method in interface lejos.robotics.RangeFinder
Get the range to the nearest object
getRange() - Method in class lejos.robotics.RangeFinderAdapter
 
getRange() - Method in class lejos.robotics.RangeReading
Get the range reading
getRange(int) - Method in class lejos.robotics.RangeReadings
Get a specific range reading
getRange(float) - Method in class lejos.robotics.RangeReadings
Get a range reading for a specific angle
getRangeFinder() - Method in class lejos.robotics.FixedRangeScanner
returns the rangeFinder - allows other objects to get a range value.
getRangeFinder() - Method in interface lejos.robotics.RangeScanner
Return the range finder for use by other classes
getRangeFinder() - Method in class lejos.robotics.RotatingRangeScanner
returns the rangeFinder - allows other objects to get a range value.
getRangeReading() - Method in interface lejos.robotics.objectdetection.Feature
Returns the RangeReading for this particular detected feature.
getRangeReading() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getRangeReadings() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns most recent range readings
getRangeReadings() - Method in interface lejos.robotics.objectdetection.Feature
Returns a set of RangeReadings for a number of detected objects.
getRangeReadings() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getRanges() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
getRanges() - Method in interface lejos.robotics.RangeFinder
If the sensor is capable, this method returns multiple range values from a single scan.
getRanges() - Method in class lejos.robotics.RangeFinderAdapter
 
getRangeValues() - Method in class lejos.robotics.FixedRangeScanner
Return a set of range readings determined taken at the relative bearings defined in the angles array; The robot rotates back to its original heading at the end.
getRangeValues() - Method in interface lejos.robotics.RangeScanner
Take a set of range readings.
getRangeValues() - Method in class lejos.robotics.RotatingRangeScanner
Returns a set of Range Readings taken the angles specified.
getRateMode() - Method in class lejos.hardware.sensor.CruizcoreGyro
Cruizcore XG1300L, Acceleration mode
Measures rate of turn over the Z-axis
getRateMode() - Method in class lejos.hardware.sensor.DexterIMUSensor
Dexter Industries dIMU Sensor, Rate Mode
The Rate mode measures the angular speed of the sensor over three axes
getRateMode() - Method in class lejos.hardware.sensor.EV3GyroSensor
EV3 Gyro sensor, Rate mode
Measures angular velocity of the sensor.
getRateMode() - Method in class lejos.hardware.sensor.HiTechnicGyro
HiTechnic Gyro sensor, Rate mode
The Rate mode measures the angular speed of the sensor over three axes
getRateMode() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Return a SensorMode object that will angular velocity data for the X, Y and Z axis.
getRawTachoCount() - Method in class lejos.hardware.sensor.RCXRotationSensor
Returns the raw values from the rotation sensor instead of degrees.
getReading(int, RangeReadings, RangeMap) - Method in class lejos.robotics.localization.MCLParticle
Get a specific reading
getReadings(RangeReadings, RangeMap) - Method in class lejos.robotics.localization.MCLParticle
 
getReadings() - Method in class lejos.robotics.localization.MCLPoseProvider
Get the current range readings
getReadings() - Method in class lejos.robotics.mapping.NavigationModel
Get the current range readings
getRectangle(int) - Method in class lejos.hardware.device.NXTCam
Get the rectangle containing a tracked object
getRed() - Method in class lejos.robotics.Color
Returns the red component in the range 0-255 in the default sRGB space.
getRedMode() - Method in class lejos.hardware.sensor.EV3ColorSensor
EV3 color sensor, Red mode
Measures the level of reflected light from the sensors RED LED.
getRedMode() - Method in class lejos.hardware.sensor.MindsensorsLightSensorArray
Return a sample provider in that measures the light reflection of a surface illuminated with a red led light.
getRedMode() - Method in class lejos.hardware.sensor.MindsensorsLineLeader
Return a sample provider in that measures the light reflection of a surface illuminated with a red led light.
getRedMode() - Method in class lejos.hardware.sensor.NXTColorSensor
get a sample provider the returns the light value when illuminated with a Red light source.
getRedMode() - Method in class lejos.hardware.sensor.NXTLightSensor
get a sample provider the returns the light value when illuminated with a Red light source.
getRedMode() - Method in class lejos.hardware.sensor.RCXLightSensor
get a sample provider the returns the light value when illuminated with a Red light source.
getRefreshCompleteTime() - Static method in class lejos.hardware.lcd.LCD
Obtain the system time when the current display refresh operation will be complete.
getRegulatedMotor(int) - Method in class lejos.hardware.device.NXTMMX
Get a MMXRegulatedMotor instance that is associated with the motorID.
getRegulatedMotor(int) - Method in class lejos.hardware.device.tetrix.TetrixMotorController
Get a TetrixRegulatedMotor instance that is associated with the motorID.
getRegulator() - Method in interface lejos.hardware.port.TachoMotorPort
Return the motor regulator associated with this motor port.
getRegulator() - Method in class lejos.remote.ev3.RemoteMotorPort
 
getRegulator() - Method in class lejos.remote.ev3.RemoteRequestMotorPort
 
getRegulator() - Method in class lejos.remote.nxt.RemoteNXTMotorPort
 
getRemoteCommand(int) - Method in class lejos.hardware.sensor.EV3IRSensor
Return the current remote command from the specified channel.
getRemoteCommands(byte[], int, int) - Method in class lejos.hardware.sensor.EV3IRSensor
Obtain the commands associated with one or more channels.
getReply(int) - Method in class lejos.hardware.sensor.MindsensorsBTSense
 
getResolution() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getRetryCount() - Method in class lejos.hardware.sensor.I2CSensor
Return the current get/send retry count value
getReverse() - Method in class lejos.robotics.chassis.WheeledChassis
 
getRGBMode() - Method in class lejos.hardware.sensor.EV3ColorSensor
EV3 color sensor, RGB mode
Measures the level of red, green and blue light when illuminated by a white light source..
getRGBMode() - Method in class lejos.hardware.sensor.HiTechnicColorSensor
HiTechnic color sensor, Color ID mode
Measures the color of a surface.
getRGBMode() - Method in class lejos.hardware.sensor.NXTColorSensor
get a sample provider the returns the light values (RGB + ambient) when illuminated by a white light source.
getRightX() - Method in class lejos.hardware.device.PSPNXController
 
getRightY() - Method in class lejos.hardware.device.PSPNXController
 
getRobotPose() - Method in class lejos.robotics.mapping.NavigationModel
Get the current pose of the robot
getRotateSpeed() - Method in class lejos.robotics.navigation.Move
Get the rotate speed
getRotationSpeed() - Method in class lejos.hardware.device.MMXRegulatedMotor
Return the current rotational speed calculated from the encoder position every 100 ms.
getRotationSpeed() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
Return the current rotational speed calculated from the encoder position every 100 ms.
getRotationSpeed() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Return the current velocity.
getRotationSpeed() - Method in class lejos.hardware.sensor.RCXRotationSensor
 
getRotationSpeed() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
getRotationSpeed() - Method in class lejos.robotics.MirrorMotor
 
getRotationSpeed() - Method in interface lejos.robotics.Tachometer
Returns the actual speed.
getRoute(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for find path()
calculates the route backtracking through predecessor chain
getRowDimension() - Method in class lejos.utility.Matrix
Get row dimension.
getRowPackedCopy() - Method in class lejos.utility.Matrix
Make a one-dimensional row packed copy of the internal array.
getSampleNames() - Method in interface lejos.remote.ev3.Menu
 
getSampleNames() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getSampleNames() - Method in interface lejos.remote.ev3.RMIMenu
 
getSampleRate() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
getSampleRate() - Method in class lejos.robotics.filter.SampleThread
 
getSampleRates() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
getSatellite(int) - Method in class lejos.hardware.gps.GPS
Get NMEA Satellite.
getSatellite(int) - Method in class lejos.hardware.gps.GSVSentence
Return a NMEA Satellite object
getSatellitesInView() - Method in class lejos.hardware.gps.GPS
The satellites in view is a list of satellites the GPS could theoretically connect to (i.e.
getSatellitesInView() - Method in class lejos.hardware.gps.GSVSentence
Returns the number of satellites being tracked to determine the coordinates.
getSatellitesTracked() - Method in class lejos.hardware.gps.GGASentence
Returns the number of satellites being tracked to determine the coordinates.
getSatellitesTracked() - Method in class lejos.hardware.gps.GPS
Returns the number of satellites being tracked to determine the coordinates.
getSatellitesTracked() - Method in class lejos.hardware.gps.SimpleGPS
Returns the number of satellites being tracked to determine the coordinates.
getScaleCorrection() - Method in class lejos.robotics.filter.LinearCalibrationFilter
Returns an array with the scale correction paramaters that are currently in use
getScanner() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the range scanner
getSecond() - Method in interface lejos.robotics.Clock
 
getSeekMode() - Method in class lejos.hardware.sensor.EV3IRSensor
EV3 Infra Red sensor, Seek mode
In seek mode the sensor locates up to four beacons and provides bearing and distance of each beacon.
getSelectionType() - Method in class lejos.hardware.gps.SimpleGPS
Selection type of 2D or 3D fix 'M' = manual 'A' = automatic
getSensorMode(char) - Method in class lejos.hardware.sensor.MindsensorsBTSense
Get a SensorMode object for a specific sensor mode and request data from phone
getSerialNo() - Method in class lejos.hardware.sensor.RFIDSensor
Obtain the serial number of the RFID Sensor.
getServo(int) - Method in class lejos.hardware.device.LSC
Method to get an RC Servo in a LSC
getServo(int) - Method in class lejos.hardware.device.MSC
Method to get an RC Servo in from the NXTServo
getServo(int) - Method in class lejos.hardware.device.tetrix.TetrixServoController
Get the TetrixServo instance that is associated with the passed servoID.
getSetting(String) - Method in interface lejos.remote.ev3.Menu
 
getSetting(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getSetting(String) - Method in interface lejos.remote.ev3.RMIMenu
 
getShort() - Method in interface lejos.hardware.port.UARTPort
read a single short from the device.
getShort() - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
getShort() - Method in class lejos.remote.ev3.RemoteUARTPort
 
getShort() - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
getShort() - Method in interface lejos.remote.ev3.RMIUARTPort
read a single short from the device.
getShortDistanceMode() - Method in class lejos.hardware.sensor.HiTechnicEOPD
HiTechnic EOPD sensor, Short distance mode
Measures the relative distance to a surface.
getShorts(short[], int, int) - Method in interface lejos.hardware.port.UARTPort
read a number of shorts from the device
getShorts(short[], int, int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
getShorts(short[], int, int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
getShorts(short[], int, int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
getShorts(short[], int, int) - Method in interface lejos.remote.ev3.RMIUARTPort
read a number of shorts from the device
getSigmaHeading() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the standard deviation of the heading values in the particle set;
getSigmaX() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the standard deviation of the X values in the particle set;
getSigmaY() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the standard deviation of the Y values in the particle set;
getSignalNoiseRatio() - Method in class lejos.hardware.gps.Satellite
* Signal to Noise Ratio (SNR) for the signal from a satellite.
getSleepTime() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific method to get the menu sleep time
getSmallFont() - Static method in class lejos.hardware.lcd.Font
Return the small font.
getSomeMode() - Method in class lejos.hardware.sensor.CodeTemplate
Sensor name, mode
Mode description
getSource() - Method in class lejos.robotics.filter.SubscribedProvider
 
getSourceDistance() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
return the shortest path length to this node from the start node
getSources() - Static method in class lejos.robotics.filter.PublishedSource
 
getSpeed() - Method in class lejos.hardware.device.LDCMotor
Method to get speed from the DC Motor
getSpeed() - Method in class lejos.hardware.device.MMXRegulatedMotor
Return the current target speed.
getSpeed() - Method in class lejos.hardware.device.PFMateMotor
returns the speed
getSpeed(int) - Method in class lejos.hardware.device.RCXMotorMultiplexer
 
getSpeed() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
Return the speed value calculated from the actual power value as:
getSpeed() - Method in class lejos.hardware.gps.RMCSentence
Get Speed in Kilometers
getSpeed() - Method in class lejos.hardware.gps.SimpleGPS
Get speed in kilometers per hour
getSpeed() - Method in class lejos.hardware.gps.VTGSentence
Get Speed in Kilometers
getSpeed() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Return the current target speed.
getSpeed() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
getSpeed() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Returns the current motor speed.
getSpeed() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
getSpeed() - Method in class lejos.robotics.MirrorMotor
 
getSpeed() - Method in interface lejos.robotics.RegulatedMotor
Returns the current motor speed.
getStandardDeviation() - Method in class lejos.robotics.filter.OffsetCorrectionFilter
Returns the standard deviation from the mean sample value
getStatus() - Method in class lejos.hardware.device.RCXLink
 
getStatus() - Method in class lejos.hardware.gps.RMCSentence
 
getStatus() - Method in class lejos.hardware.sensor.RFIDSensor
Read the status from the device.
getStatus() - Method in class lejos.remote.nxt.RemoteNXTI2CPort
 
getStepTime() - Method in class lejos.hardware.device.tetrix.TetrixServoController
Gets the step time used for all servos on this controller.
getStrokeStyle() - Method in interface lejos.hardware.lcd.GraphicsLCD
Return the current stroke style.
getStrokeStyle() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getStrokeStyle() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getStrokeStyle() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getStrokeStyle() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getSystemFont() - Static method in class lejos.hardware.lcd.LCD
Provide access to the LCD system font.
getTachoCount() - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Returns the absolute tachometer (encoder) position of the actuator shaft.
getTachoCount() - Method in class lejos.hardware.device.MMXMotor
 
getTachoCount() - Method in class lejos.hardware.device.tetrix.TetrixEncoderMotor
 
getTachoCount() - Method in class lejos.hardware.motor.BaseRegulatedMotor
 
getTachoCount() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
getTachoCount() - Method in interface lejos.hardware.motor.MotorRegulator
Get the current hardware tachometer reading for the motor,
getTachoCount() - Method in interface lejos.hardware.motor.Tachometer
 
getTachoCount() - Method in class lejos.hardware.motor.UnregulatedMotor
 
getTachoCount() - Method in class lejos.hardware.sensor.RCXRotationSensor
Returns the tachometer count.
getTachoCount() - Method in class lejos.remote.ev3.RemoteMotorPort
returns tachometer count
getTachoCount() - Method in class lejos.remote.ev3.RemoteRequestMotorPort
 
getTachoCount() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
getTachoCount() - Method in interface lejos.remote.ev3.RMIMotorPort
returns tachometer count
getTachoCount() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
 
getTachoCount() - Method in class lejos.remote.ev3.RMIRemoteMotorPort
 
getTachoCount() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
getTachoCount(int) - Method in class lejos.remote.nxt.NXTCommand
Retrieves tacho count.
getTachoCount() - Method in class lejos.remote.nxt.RemoteNXTMotorPort
returns tachometer count
getTachoCount() - Method in interface lejos.robotics.Encoder
Returns the tachometer count.
getTachoCount() - Method in interface lejos.robotics.LinearActuator
Returns the absolute tachometer (encoder) position of the actuator shaft.
getTachoCount() - Method in class lejos.robotics.MirrorMotor
 
getTarget() - Method in class lejos.robotics.mapping.NavigationModel
Get the target waypoint
getTemperatureMode() - Method in class lejos.hardware.sensor.DexterIMUSensor
Dexter Industries dIMU Sensor, Temperature Mode
The Temperature mode measures the internal temperature of the sensors gyroscope IC
getTemperatureMode() - Method in class lejos.hardware.sensor.HiTechnicBarometer
HiTechnic Barometer, Temperature mode
Measures the temperature of the air.
getTemperatureMode() - Method in class lejos.hardware.sensor.RCXThermometer
Return a sample provider in temperature mode
getTextHeight() - Method in interface lejos.hardware.lcd.TextLCD
Get the height of the screen in characters
getTextHeight() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
getTextHeight() - Method in class lejos.remote.ev3.RemoteTextLCD
 
getTextHeight() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
getTextHeight() - Method in interface lejos.remote.ev3.RMITextLCD
 
getTextLCD() - Method in interface lejos.hardware.Brick
Get text access to the LCD using the default font
getTextLCD(Font) - Method in interface lejos.hardware.Brick
Get text access to the LCD using a specified font
getTextLCD() - Method in class lejos.hardware.ev3.LocalEV3
 
getTextLCD(Font) - Method in class lejos.hardware.ev3.LocalEV3
 
getTextLCD() - Method in class lejos.remote.ev3.RemoteEV3
 
getTextLCD(Font) - Method in class lejos.remote.ev3.RemoteEV3
 
getTextLCD() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getTextLCD(Font) - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getTextLCD() - Method in interface lejos.remote.ev3.RMIEV3
 
getTextLCD(Font) - Method in interface lejos.remote.ev3.RMIEV3
 
getTextLCD() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getTextLCD(Font) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getTextLCD() - Method in class lejos.remote.nxt.RemoteNXT
 
getTextLCD(Font) - Method in class lejos.remote.nxt.RemoteNXT
 
getTextWidth() - Method in interface lejos.hardware.lcd.TextLCD
Get the width of the screen in characters
getTextWidth() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
getTextWidth() - Method in class lejos.remote.ev3.RemoteTextLCD
 
getTextWidth() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
getTextWidth() - Method in interface lejos.remote.ev3.RMITextLCD
 
getTiltMode() - Method in class lejos.hardware.sensor.MindsensorsAccelerometer
Return a SampleProvider that provides tilt data (in degree) in X, Y, Z axis
getTime() - Method in class lejos.hardware.gps.GGASentence
Returns the last time stamp retrieved from a satellite
getTime() - Method in class lejos.hardware.gps.RMCSentence
Get time in integer format
getTime() - Static method in class lejos.hardware.Sound
Returns the number of milliseconds remaining of the current tone or sample.
getTime() - Method in class lejos.robotics.filter.PublishedSource
 
getTime() - Method in class lejos.robotics.filter.SubscribedProvider
 
getTimeMode() - Method in class lejos.hardware.sensor.DexterGPSSensor
Dexter dGPS sensor, Time mode
gets the UTC time from the sensor
getTimeOut() - Method in class lejos.remote.rcx.RCXAbstractPort
Getter for property timeOut.
getTimeStamp() - Method in class lejos.hardware.gps.SimpleGPS
Get the last time stamp from the satellite for GGA sentence.
getTimeStamp() - Method in class lejos.robotics.filter.PublishedSource
 
getTimeStamp() - Method in class lejos.robotics.filter.SubscribedProvider
 
getTimeStamp() - Method in class lejos.robotics.navigation.Move
The time stamp is the system clock at the time the Move object is created.
getTimeStamp() - Method in interface lejos.robotics.objectdetection.Feature
The time-stamp is the recorded system time when the range reading was taken.
getTimeStamp() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getTimeString() - Method in interface lejos.robotics.Clock
 
getTouchMode() - Method in class lejos.hardware.sensor.EV3TouchSensor
Lego EV3 Touch sensor, Touch mode
Detects when its front button is pressed
getTouchMode() - Method in class lejos.hardware.sensor.NXTTouchSensor
get a sample provider that returns an indication of the button being up(0) or down(1)
getTranslateX() - Method in interface lejos.hardware.lcd.GraphicsLCD
Gets the X coordinate of the translated origin of this graphics context.
getTranslateX() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getTranslateX() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getTranslateX() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getTranslateX() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getTranslateY() - Method in interface lejos.hardware.lcd.GraphicsLCD
Gets the Y coordinate of the translated origin of this graphics context.
getTranslateY() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getTranslateY() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getTranslateY() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getTranslateY() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getTravelSpeed() - Method in class lejos.robotics.navigation.Move
Get the travel speed
getTriangleAngle(Point, Point, Point) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method calculates the angle generated by three points.
getTrueCourse() - Method in class lejos.hardware.gps.VTGSentence
Get true course, in degrees.
getTurnRate() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Get the turn rate for arc and steer commands
getType() - Method in interface lejos.hardware.Brick
Get the type of brick, e.g.
getType() - Method in class lejos.hardware.BrickInfo
 
getType() - Method in class lejos.hardware.device.SensorMux
Return the type
getType() - Method in class lejos.hardware.ev3.LocalEV3
 
getType() - Method in interface lejos.hardware.port.BasicSensorPort
Get the current type setting.
getType() - Method in class lejos.remote.ev3.RemoteEV3
 
getType() - Method in class lejos.remote.ev3.RemoteIOPort
 
getType() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getType() - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
getType() - Method in class lejos.remote.nxt.RemoteNXT
 
getType() - Method in class lejos.remote.nxt.RemoteNXTIOPort
Get the current type setting.
getU(int, int) - Method in class lejos.hardware.video.YUYVImage
return the U component of the specified pixel
getU() - Method in class lejos.utility.LUDecomposition
Return upper triangular factor
getUARTSignature() - Method in class lejos.hardware.device.DeviceIdentifier
Returns the signature for a UART sensor
getUnmodulatedMode() - Method in class lejos.hardware.sensor.HiTechnicIRSeeker
HiTechnic IR seeker, Unmodulated mode
Measures the angle to a source of unmodulated infrared light
getUnmodulatedMode() - Method in class lejos.hardware.sensor.HiTechnicIRSeekerV2
HiTechnic IR seeker V2, Unmodulated mode
Measures the angle to a source of unmodulated infrared light
getV(int, int) - Method in class lejos.hardware.video.YUYVImage
return the V component of the specified pixel
getValue() - Method in class lejos.hardware.sensor.SumoEyesSensor
Gets the raw value of the sensor.
getVDOP() - Method in class lejos.hardware.gps.GSASentence
Return VDOP
getVDOP() - Method in class lejos.hardware.gps.SimpleGPS
Get the Vertical Dilution of Precision (VDOP).
getVelocityMode() - Method in class lejos.hardware.sensor.DexterGPSSensor
Dexter dGPS sensor, Velocity mode
Gets the velocity (speed) of the sensor
getVendorID() - Method in class lejos.hardware.sensor.DexterThermalIRSensor
 
getVendorID() - Method in class lejos.hardware.sensor.I2CSensor
Read the sensor's vendor identifier.
getVersion() - Method in class lejos.hardware.sensor.I2CSensor
Read the sensor's version string.
getVersion() - Method in interface lejos.remote.ev3.Menu
 
getVersion() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
getVersion() - Method in interface lejos.remote.ev3.RMIMenu
 
getVideo() - Method in interface lejos.hardware.Brick
 
getVideo() - Method in class lejos.hardware.ev3.LocalEV3
getVideo() - Method in class lejos.remote.ev3.RemoteEV3
 
getVideo() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getVideo() - Method in class lejos.remote.nxt.RemoteNXT
 
getVisibility() - Method in class lejos.hardware.LocalBTDevice
return the current visibility of the device
getVisibility() - Method in interface lejos.remote.ev3.RMIBluetooth
 
getVisibility() - Method in class lejos.remote.ev3.RMIRemoteBluetooth
 
getVoltage() - Static method in class lejos.hardware.Battery
 
getVoltage() - Method in class lejos.hardware.device.NXTMMX
Returns the voltage supplied to the NXTMMX
getVoltage() - Method in class lejos.hardware.device.tetrix.TetrixMotorController
Return the current battery voltage supplied to the controller.
getVoltage() - Method in interface lejos.hardware.Power
The NXT uses 6 batteries of 1.5 V each.
getVoltage() - Method in class lejos.remote.ev3.RemoteBattery
 
getVoltage() - Method in class lejos.remote.ev3.RemoteRequestBattery
 
getVoltage() - Method in interface lejos.remote.ev3.RMIBattery
The NXT uses 6 batteries of 1.5 V each.
getVoltage() - Method in class lejos.remote.ev3.RMIRemoteBattery
 
getVoltage() - Method in class lejos.remote.nxt.RemoteNXTBattery
The NXT uses 6 batteries of 1.5 V each.
getVoltageMilliVolt() - Static method in class lejos.hardware.Battery
 
getVoltageMilliVolt() - Method in interface lejos.hardware.Power
The NXT uses 6 batteries of 1500 mV each.
getVoltageMilliVolt() - Method in class lejos.remote.ev3.RemoteBattery
 
getVoltageMilliVolt() - Method in class lejos.remote.ev3.RemoteRequestBattery
 
getVoltageMilliVolt() - Method in interface lejos.remote.ev3.RMIBattery
The NXT uses 6 batteries of 1500 mV each.
getVoltageMilliVolt() - Method in class lejos.remote.ev3.RMIRemoteBattery
 
getVoltageMilliVolt() - Method in class lejos.remote.nxt.RemoteNXTBattery
The NXT uses 6 batteries of 1500 mV each.
getVoltageMode() - Method in class lejos.hardware.sensor.MindsensorsDistanceSensorV2
Returns a sample provider that measures the output level (in volt) of the sensors signal processing unit.
getVolume() - Method in interface lejos.hardware.Audio
Get the current master volume level
getVolume() - Static method in class lejos.hardware.Sound
Get the current master volume level
getVolume() - Method in class lejos.remote.ev3.RemoteAudio
 
getVolume() - Method in class lejos.remote.ev3.RemoteRequestAudio
 
getVolume() - Method in interface lejos.remote.ev3.RMIAudio
Get the current master volume level
getVolume() - Method in class lejos.remote.ev3.RMIRemoteAudio
 
getVolume() - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to get the master volume level
getVolume() - Method in class lejos.remote.nxt.RemoteNXTAudio
 
getWaypoint() - Method in class lejos.robotics.navigation.Navigator
Returns the waypoint to which the robot is presently moving.
getWeight() - Method in class lejos.robotics.localization.MCLParticle
Return the weight of this particle
getWidth() - Method in interface lejos.hardware.lcd.CommonLCD
Return the width of the associated drawing surface.
getWidth() - Method in class lejos.hardware.lcd.Image
Return the width of the image.
getWidth() - Method in interface lejos.hardware.video.Video
Return the frame width
getWidth() - Method in class lejos.hardware.video.YUYVImage
return the image width
getWidth() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
getWidth() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
getWidth() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
getWidth() - Method in class lejos.remote.ev3.RemoteTextLCD
 
getWidth() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
getWidth() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
getWidth() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
getWidth() - Method in interface lejos.remote.ev3.RMITextLCD
 
getWidth() - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
getWidth() - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
getWidth() - Method in class lejos.robotics.geometry.RectangleInt32
Get the width as a double
getWidth() - Method in class lejos.robotics.geometry.RectangularShape
Get the width as a double
getWidth() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getWifi() - Method in class lejos.remote.ev3.RemoteEV3
 
getWifi() - Method in interface lejos.remote.ev3.RMIEV3
 
getWifi() - Method in class lejos.remote.ev3.RMIRemoteEV3
 
getWifiDevice() - Method in interface lejos.hardware.Brick
Get the local Wifi device
getWifiDevice() - Method in class lejos.hardware.ev3.LocalEV3
 
getWifiDevice() - Method in class lejos.remote.ev3.RemoteEV3
 
getWifiDevice() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
getWifiDevice() - Method in class lejos.remote.nxt.RemoteNXT
 
getX() - Method in class lejos.robotics.geometry.Point2D.Double
 
getX() - Method in class lejos.robotics.geometry.Point2D.Float
 
getX() - Method in class lejos.robotics.geometry.Point2D
Get the x coordinate as a double
getX() - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
getX() - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
getX() - Method in class lejos.robotics.geometry.RectangleInt32
Get the x coordinate as a double
getX() - Method in class lejos.robotics.geometry.RectangularShape
Get the x coordinate as a double
getX() - Method in class lejos.robotics.navigation.Pose
Get the X coordinate
getX() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the X coordinate of this node
getX1() - Method in class lejos.robotics.geometry.Line2D.Double
 
getX1() - Method in class lejos.robotics.geometry.Line2D.Float
 
getX1() - Method in class lejos.robotics.geometry.Line2D
Get the x coordinate of the start of the line
getX2() - Method in class lejos.robotics.geometry.Line2D.Double
 
getX2() - Method in class lejos.robotics.geometry.Line2D.Float
 
getX2() - Method in class lejos.robotics.geometry.Line2D
Get the x coordinate of the end of the line
getXAccel() - Method in interface lejos.robotics.Accelerometer
Measures the x-axis of the accelerometer, in meters/second^2.
getXAccel() - Method in class lejos.robotics.AccelerometerAdapter
 
getXRange() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the difference between max X and min X
getY(int, int) - Method in class lejos.hardware.video.YUYVImage
return the Y component of the specified pixel
getY() - Method in class lejos.robotics.geometry.Point2D.Double
 
getY() - Method in class lejos.robotics.geometry.Point2D.Float
 
getY() - Method in class lejos.robotics.geometry.Point2D
Get the y coordinate as a double
getY() - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
getY() - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
getY() - Method in class lejos.robotics.geometry.RectangleInt32
Get the y coordinate as a double
getY() - Method in class lejos.robotics.geometry.RectangularShape
Get the y coordinate as a double
getY() - Method in class lejos.robotics.navigation.Pose
Get the Y coordinate
getY() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the Y coordinate of thes Node
getY1() - Method in class lejos.robotics.geometry.Line2D.Double
 
getY1() - Method in class lejos.robotics.geometry.Line2D.Float
 
getY1() - Method in class lejos.robotics.geometry.Line2D
Get the y coordinate of the start of the line
getY2() - Method in class lejos.robotics.geometry.Line2D.Double
 
getY2() - Method in class lejos.robotics.geometry.Line2D.Float
 
getY2() - Method in class lejos.robotics.geometry.Line2D
Get the y coordinate of the end of the line
getYAccel() - Method in interface lejos.robotics.Accelerometer
Measures the y-axis of the accelerometer, in meters/second^2.
getYAccel() - Method in class lejos.robotics.AccelerometerAdapter
 
getYear() - Method in interface lejos.robotics.Clock
 
getYRange() - Method in class lejos.robotics.localization.MCLPoseProvider
Return difference between max Y and min Y
getZAccel() - Method in interface lejos.robotics.Accelerometer
Measures the z-axis of the accelerometer, in meters/second^2.
getZAccel() - Method in class lejos.robotics.AccelerometerAdapter
 
GGASentence - Class in lejos.hardware.gps
This class has been designed to manage a GGA Sentence GGA - essential fix data which provide 3D location and accuracy data.
GGASentence() - Constructor for class lejos.hardware.gps.GGASentence
 
ggaSentence - Variable in class lejos.hardware.gps.SimpleGPS
 
glyphCount - Variable in class lejos.hardware.lcd.Font
 
glyphs - Variable in class lejos.hardware.lcd.Font
 
glyphWidth - Variable in class lejos.hardware.lcd.Font
 
go() - Method in class lejos.robotics.subsumption.Arbitrator
This method starts the arbitration of Behaviors and runs an endless loop.
goTo(Waypoint) - Method in class lejos.robotics.navigation.Navigator
Starts the robot moving toward the destination.
goTo(float, float) - Method in class lejos.robotics.navigation.Navigator
Starts the moving toward the destination Waypoint created from the parameters.
goTo(float, float, float) - Method in class lejos.robotics.navigation.Navigator
Starts the moving toward the destination Waypoint created from the parameters.
goToInitAngle() - Method in class lejos.hardware.device.LServo
Method to set medium angle
goToMaxAngle() - Method in class lejos.hardware.device.LServo
Method to set maximum angle
goToMiddleAngle() - Method in class lejos.hardware.device.LServo
Method to set medium angle
goToMinAngle() - Method in class lejos.hardware.device.LServo
Method to set minimal angle
GPS - Class in lejos.hardware.gps
This class manages data received from a GPS Device.
GPS(InputStream) - Constructor for class lejos.hardware.gps.GPS
The constructor.
GPSListener - Interface in lejos.hardware.gps
This is the interface to manage events with GPS
grabFrame(byte[]) - Method in interface lejos.hardware.video.Video
Grab a single frame from the device and store the image into the supplied array
graphicsLCD - Variable in class lejos.hardware.ev3.LocalEV3
 
GraphicsLCD - Interface in lejos.hardware.lcd
 
GRAY - Static variable in class lejos.robotics.Color
 
GREEN - Static variable in interface lejos.hardware.sensor.SensorConstants
 
GREEN - Static variable in class lejos.robotics.Color
 
GREEN_INDEX - Static variable in interface lejos.hardware.sensor.SensorConstants
Color sensor data GREEN value index.
GridNode - Class in lejos.robotics.pathfinding
 
GridNode(float, float, float) - Constructor for class lejos.robotics.pathfinding.GridNode
 
GSASentence - Class in lejos.hardware.gps
This class has been designed to manage a GSA Sentence GPS DOP and active satellites eg1.
GSASentence() - Constructor for class lejos.hardware.gps.GSASentence
Constructor
gsaSentence - Variable in class lejos.hardware.gps.SimpleGPS
 
GSVSentence - Class in lejos.hardware.gps
This class has been designed to manage a GSV Sentence GPS Satellites in view eg.
GSVSentence() - Constructor for class lejos.hardware.gps.GSVSentence
 
GYRO_DATA - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
GYRO_FILTER - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
Gyro_I2C_address - Variable in class lejos.hardware.sensor.DexterIMUSensor
 
GyroDirectionFinder - Class in lejos.utility
Implementation of the DirectionFinder interface that integrates repeated rate-of-turn readings from a gyro sensor into a continuously updated heading.
GyroDirectionFinder(Gyroscope) - Constructor for class lejos.utility.GyroDirectionFinder
Creates and initializes a new GyroDirectionFinder using passed GyroSensor
GyroDirectionFinder(Gyroscope, boolean) - Constructor for class lejos.utility.GyroDirectionFinder
Creates and initializes a new GyroDirectionFinder using passed GyroSensor and does the GyroSensor.recalibrateOffset() method.
gyroMode - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
Gyroscope - Interface in lejos.robotics
Abstraction for Gyroscope defines minimal implementation
GyroscopeAdapter - Class in lejos.robotics
Provides an adapter that implements the Gyroscope interface.
GyroscopeAdapter(SampleProvider, float, int) - Constructor for class lejos.robotics.GyroscopeAdapter
 
GyroscopeAdapter(SampleProvider, float) - Constructor for class lejos.robotics.GyroscopeAdapter
 

H

halt() - Method in class lejos.robotics.LightScanner
 
HANDLE_ALREADY_CLOSED - Static variable in class lejos.remote.nxt.ErrorMessages
 
hasMap() - Method in class lejos.robotics.mapping.NavigationModel
Test is the model has a map registered
HCENTER - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Centering text and images horizontally around the anchor point
head - Variable in class lejos.robotics.LightScanner
 
head - Variable in class lejos.robotics.RotatingRangeScanner
 
HEADER - Static variable in class lejos.hardware.gps.GGASentence
 
HEADER - Static variable in class lejos.hardware.gps.GSASentence
 
HEADER - Static variable in class lejos.hardware.gps.GSVSentence
 
HEADER - Static variable in class lejos.hardware.gps.RMCSentence
 
HEADER - Static variable in class lejos.hardware.gps.VTGSentence
 
heading - Variable in class lejos.robotics.navigation.Waypoint
 
headingRequired - Variable in class lejos.robotics.navigation.Waypoint
 
height - Variable in class lejos.hardware.lcd.Font
 
height - Variable in class lejos.robotics.geometry.Rectangle2D.Double
The height of the rectangle;
height - Variable in class lejos.robotics.geometry.Rectangle2D.Float
The height of the rectangle;
height - Variable in class lejos.robotics.geometry.RectangleInt32
The height of the rectangle
HIGH - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
HIGH_SPEED_BUFFER - Static variable in interface lejos.remote.nxt.NXTProtocol
 
HiTechnicAccelerometer - Class in lejos.hardware.sensor
HiTechnic NXT Acceleration / Tilt Sensor (NAC1040)
The HiTechnic Accelerometer / Tilt Sensor measures acceleration in three axes.
HiTechnicAccelerometer(I2CPort, int) - Constructor for class lejos.hardware.sensor.HiTechnicAccelerometer
Creates a SampleProvider for the HiTechnic Acceleration Sensor
HiTechnicAccelerometer(I2CPort) - Constructor for class lejos.hardware.sensor.HiTechnicAccelerometer
Creates a SampleProvider for the HiTechnic Acceleration Sensor
HiTechnicAccelerometer(Port, int) - Constructor for class lejos.hardware.sensor.HiTechnicAccelerometer
Creates a SampleProvider for the HiTechnic Acceleration Sensor
HiTechnicAccelerometer(Port) - Constructor for class lejos.hardware.sensor.HiTechnicAccelerometer
Creates a SampleProvider for the HiTechnic Acceleration Sensor
HiTechnicAngleSensor - Class in lejos.hardware.sensor
Hitechnic Angle sensor
The Angle sensor measures axle rotation position and rotation speed.
HiTechnicAngleSensor(I2CPort) - Constructor for class lejos.hardware.sensor.HiTechnicAngleSensor
 
HiTechnicAngleSensor(Port) - Constructor for class lejos.hardware.sensor.HiTechnicAngleSensor
 
HiTechnicBarometer - Class in lejos.hardware.sensor
Hitechnic Barometric sensor
The sensor measures both atmospheric pressure and temperature.
HiTechnicBarometer(I2CPort) - Constructor for class lejos.hardware.sensor.HiTechnicBarometer
Constructor.
HiTechnicBarometer(I2CPort, int) - Constructor for class lejos.hardware.sensor.HiTechnicBarometer
Constructor.
HiTechnicBarometer(Port, int) - Constructor for class lejos.hardware.sensor.HiTechnicBarometer
 
HiTechnicBarometer(Port) - Constructor for class lejos.hardware.sensor.HiTechnicBarometer
 
HiTechnicColorSensor - Class in lejos.hardware.sensor
HiTechnic color sensor
Description

The code for this sensor has not been tested.

HiTechnicColorSensor(I2CPort) - Constructor for class lejos.hardware.sensor.HiTechnicColorSensor
 
HiTechnicColorSensor(Port) - Constructor for class lejos.hardware.sensor.HiTechnicColorSensor
 
HiTechnicColorSensor.RGBMode - Class in lejos.hardware.sensor
 
HiTechnicCompass - Class in lejos.hardware.sensor
HiTechnic compass sensor Sensor name
The HiTechnic compass measures the earth's magnetic field and calculates a heading angle.
HiTechnicCompass(I2CPort, int) - Constructor for class lejos.hardware.sensor.HiTechnicCompass
Create a compass sensor object
HiTechnicCompass(I2CPort) - Constructor for class lejos.hardware.sensor.HiTechnicCompass
Create a compass sensor object
HiTechnicCompass(Port, int) - Constructor for class lejos.hardware.sensor.HiTechnicCompass
Create a compass sensor object
HiTechnicCompass(Port) - Constructor for class lejos.hardware.sensor.HiTechnicCompass
Create a compass sensor object
HiTechnicEOPD - Class in lejos.hardware.sensor
HiTechnic EOPD Sensor
The EOPD or Electro Optical Proximity Detector uses an internal light source to detect the presence of a target or determine changes in distance to a target.
HiTechnicEOPD(AnalogPort) - Constructor for class lejos.hardware.sensor.HiTechnicEOPD
 
HiTechnicEOPD(Port) - Constructor for class lejos.hardware.sensor.HiTechnicEOPD
 
HiTechnicEOPD.ShortDistanceMode - Class in lejos.hardware.sensor
 
HiTechnicGyro - Class in lejos.hardware.sensor
HiTechnic NXT Gyro Sensor
The NXT Gyro Sensor contains a single axis gyroscopic sensor that detects rotation.
HiTechnicGyro(AnalogPort) - Constructor for class lejos.hardware.sensor.HiTechnicGyro
Supports the SampleProvider interface.
HiTechnicGyro(Port) - Constructor for class lejos.hardware.sensor.HiTechnicGyro
Supports the SampleProvider interface.
HiTechnicIRSeeker - Class in lejos.hardware.sensor
HiTechnic NXT IRSeeker
The NXT IRSeeker is a multi-element infrared detector that detects infrared signals from sources such as the HiTechnic IRBall soccer ball, infrared remote controls and sunlight.
HiTechnicIRSeeker(I2CPort) - Constructor for class lejos.hardware.sensor.HiTechnicIRSeeker
 
HiTechnicIRSeeker(Port) - Constructor for class lejos.hardware.sensor.HiTechnicIRSeeker
 
HiTechnicIRSeekerV2 - Class in lejos.hardware.sensor
HiTechnic NXT IRSeeker V2
The NXT IRSeeker V2 (Version 2) is a multi-element infrared detector that detects infrared signals from sources such as the HiTechnic IRBall soccer ball, infrared remote controls and sunlight.
HiTechnicIRSeekerV2(I2CPort) - Constructor for class lejos.hardware.sensor.HiTechnicIRSeekerV2
 
HiTechnicIRSeekerV2(Port) - Constructor for class lejos.hardware.sensor.HiTechnicIRSeekerV2
 
HiTechnicMagneticSensor - Class in lejos.hardware.sensor

The sensor detects magnetic fields that are present around the front of the sensor in a vertical orientation.
HiTechnicMagneticSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.HiTechnicMagneticSensor
Create a magnetic sensor on an analog port
HiTechnicMagneticSensor(Port) - Constructor for class lejos.hardware.sensor.HiTechnicMagneticSensor
Create a magnetic sensor on a sensor port
HolonomicModeler(RegulatedMotor, double) - Constructor for class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
Creates a modeler object to model a robot wheel
host - Variable in class lejos.robotics.filter.PublishedSource
 
host - Variable in class lejos.robotics.filter.PublishFilter
 
HTANGLE_MODE_CALIBRATE - Static variable in class lejos.hardware.sensor.HiTechnicAngleSensor
 
HTANGLE_MODE_RESET - Static variable in class lejos.hardware.sensor.HiTechnicAngleSensor
 

I

I2CException - Exception in lejos.hardware.port
 
I2CException() - Constructor for exception lejos.hardware.port.I2CException
 
I2CException(String) - Constructor for exception lejos.hardware.port.I2CException
 
I2CException(Throwable) - Constructor for exception lejos.hardware.port.I2CException
 
I2CException(String, Throwable) - Constructor for exception lejos.hardware.port.I2CException
 
I2CPort - Interface in lejos.hardware.port
Abstraction for a port that supports I2C sensors.
I2CSensor - Class in lejos.hardware.sensor
Class that implements common methods for all I2C sensors.
I2CSensor(I2CPort, int) - Constructor for class lejos.hardware.sensor.I2CSensor
Create the sensor using an already open sensor port.
I2CSensor(I2CPort) - Constructor for class lejos.hardware.sensor.I2CSensor
 
I2CSensor(Port, int, int) - Constructor for class lejos.hardware.sensor.I2CSensor
Create the sensor using the specified port.
I2CSensor(Port) - Constructor for class lejos.hardware.sensor.I2CSensor
 
I2CSensor(Port, int) - Constructor for class lejos.hardware.sensor.I2CSensor
 
i2cTransaction(int, byte[], int, int, byte[], int, int) - Method in interface lejos.hardware.port.I2CPort
High level i2c interface.
i2cTransaction(int, byte[], int, int, byte[], int, int) - Method in class lejos.remote.ev3.RemoteI2CPort
 
i2cTransaction(int, byte[], int, int, byte[], int, int) - Method in class lejos.remote.ev3.RemoteRequestI2CPort
 
i2cTransaction(int, byte[], int, int, int) - Method in interface lejos.remote.ev3.RMII2CPort
High level i2c interface.
i2cTransaction(int, byte[], int, int, int) - Method in class lejos.remote.ev3.RMIRemoteI2CPort
 
i2cTransaction(int, byte[], int, int, byte[], int, int) - Method in class lejos.remote.nxt.RemoteNXTI2CPort
High level i2c interface.
ID_ALL - Static variable in class lejos.hardware.Button
 
ID_ALL - Static variable in interface lejos.hardware.Keys
 
ID_DOWN - Static variable in class lejos.hardware.Button
 
ID_DOWN - Static variable in class lejos.hardware.ev3.LocalEV3
 
ID_DOWN - Static variable in interface lejos.hardware.Keys
 
ID_ENTER - Static variable in class lejos.hardware.Button
 
ID_ENTER - Static variable in class lejos.hardware.ev3.LocalEV3
 
ID_ENTER - Static variable in interface lejos.hardware.Keys
 
ID_ESCAPE - Static variable in class lejos.hardware.Button
 
ID_ESCAPE - Static variable in class lejos.hardware.ev3.LocalEV3
 
ID_ESCAPE - Static variable in interface lejos.hardware.Keys
 
ID_HASH - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY0 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY1 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY2 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY3 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY4 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY5 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY6 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY7 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY8 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_KEY9 - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_LEFT - Static variable in class lejos.hardware.Button
 
ID_LEFT - Static variable in class lejos.hardware.ev3.LocalEV3
 
ID_LEFT - Static variable in interface lejos.hardware.Keys
 
ID_RIGHT - Static variable in class lejos.hardware.Button
 
ID_RIGHT - Static variable in class lejos.hardware.ev3.LocalEV3
 
ID_RIGHT - Static variable in interface lejos.hardware.Keys
 
ID_STAR - Static variable in class lejos.hardware.device.MindSensorsNumPad
 
ID_T1 - Static variable in class lejos.hardware.device.TouchMUX
Bit ID returned by readSensors when sensor T1 is pressed
ID_T2 - Static variable in class lejos.hardware.device.TouchMUX
Bit ID returned by readSensors when sensor T1 is pressed
ID_T3 - Static variable in class lejos.hardware.device.TouchMUX
Bit ID returned by readSensors when sensor T1 is pressed
ID_UP - Static variable in class lejos.hardware.Button
 
ID_UP - Static variable in class lejos.hardware.ev3.LocalEV3
 
ID_UP - Static variable in interface lejos.hardware.Keys
 
identity(int, int) - Static method in class lejos.utility.Matrix
Generate identity matrix
IIC_DATA_LENGTH - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
ILLEGAL_FILE_NAME - Static variable in class lejos.remote.nxt.ErrorMessages
 
ILLEGAL_HANDLE - Static variable in class lejos.remote.nxt.ErrorMessages
 
ILLEGAL_MAILBOX_QUEUE_ID_SPECIFIED - Static variable in class lejos.remote.nxt.ErrorMessages
 
ILLEGAL_SIZE_SPECIFIED - Static variable in class lejos.remote.nxt.ErrorMessages
 
Image - Class in lejos.hardware.lcd
Provides support for in memory images.
Image(int, int, byte[]) - Constructor for class lejos.hardware.lcd.Image
Create an image using an already existing byte array.
image - Variable in class lejos.remote.ev3.EV3Request
 
impulseMove(int, int) - Method in class lejos.robotics.navigation.Ballbot
Causes movement along either the xaxis or y axis.
inc - Static variable in class lejos.hardware.sensor.RCXRotationSensor
The following table when indexed by [previous phase][current phase] provides the current direction of rotation.
inCandidateSet(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for findPath; check if aNode is in the set of candidate nodes
inCandidateSet(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
helper method for findPath; check if aNode is in the set of candidate nodes
incomplete() - Method in class lejos.robotics.RangeReadings
Return true if the readings are incomplete
incompleteRanges() - Method in class lejos.robotics.localization.MCLPoseProvider
returns range scanner failure status
init() - Method in class lejos.hardware.device.MindSensorsNumPad
 
init() - Method in class lejos.hardware.sensor.CodeTemplate
Configures the sensor for first use and registers the supported modes
init() - Method in class lejos.hardware.sensor.CruizcoreGyro
 
init() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
init() - Method in class lejos.hardware.sensor.DexterGPSSensor
 
init() - Method in class lejos.hardware.sensor.DexterLaserSensor
 
init() - Method in class lejos.hardware.sensor.DexterPressureSensor250
 
init() - Method in class lejos.hardware.sensor.DexterPressureSensor500
 
init() - Method in class lejos.hardware.sensor.DexterThermalIRSensor
 
init() - Method in class lejos.hardware.sensor.EV3IRSensor
 
init() - Method in class lejos.hardware.sensor.EV3TouchSensor
 
init() - Method in class lejos.hardware.sensor.EV3UltrasonicSensor
 
init() - Method in class lejos.hardware.sensor.HiTechnicAccelerometer
 
init() - Method in class lejos.hardware.sensor.HiTechnicAngleSensor
 
init() - Method in class lejos.hardware.sensor.HiTechnicBarometer
 
init() - Method in class lejos.hardware.sensor.HiTechnicColorSensor
 
init() - Method in class lejos.hardware.sensor.HiTechnicCompass
 
init() - Method in class lejos.hardware.sensor.HiTechnicEOPD
 
init() - Method in class lejos.hardware.sensor.HiTechnicGyro
 
init() - Method in class lejos.hardware.sensor.HiTechnicIRSeeker
 
init() - Method in class lejos.hardware.sensor.HiTechnicIRSeekerV2
 
init() - Method in class lejos.hardware.sensor.HiTechnicMagneticSensor
 
init() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
init() - Method in class lejos.hardware.sensor.MindsensorsAccelerometer
 
init() - Method in class lejos.hardware.sensor.MindsensorsCompass
 
init() - Method in class lejos.hardware.sensor.MindsensorsDistanceSensorV2
 
init() - Method in class lejos.hardware.sensor.MindsensorsLightSensorArray
 
init() - Method in class lejos.hardware.sensor.MindsensorsLineLeader
 
init() - Method in class lejos.hardware.sensor.MindSensorsPressureSensor
 
init() - Method in class lejos.hardware.sensor.NXTColorSensor
 
init() - Method in class lejos.hardware.sensor.NXTLightSensor
 
init() - Method in class lejos.hardware.sensor.NXTTouchSensor
 
init() - Method in class lejos.hardware.sensor.RCXLightSensor
 
init() - Method in class lejos.hardware.sensor.RCXThermometer
 
init(I2CPort) - Static method in class lejos.remote.rcx.LLC
Initialize LLC and set port
init(Port) - Static method in class lejos.remote.rcx.LLC
Initialize LLC and set port
init() - Static method in class lejos.remote.rcx.LLC
Initialize LLC an
initialiseSensor(int) - Method in interface lejos.hardware.port.UARTPort
Initialise the attached sensor and set it to the required operating mode.
Note: This method is not normally needed as the sensor will be initialised when it is opened.
initialiseSensor(int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
initialiseSensor(int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
initialiseSensor(int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
initialiseSensor(int) - Method in interface lejos.remote.ev3.RMIUARTPort
Initialise the attached sensor and set it to the required operating mode.
Note: This method is not normally needed as the sensor will be initialised when it is opened.
initialize(byte) - Method in class lejos.hardware.device.PFLink
Should be called once to set up the NRLink for usage in the program
initialize() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
initLCD() - Method in class lejos.hardware.ev3.LocalEV3
 
initModes() - Method in class lejos.hardware.sensor.EV3ColorSensor
 
initSensor() - Method in class lejos.remote.nxt.RemoteNXTI2CPort
 
InputConnection - Interface in lejos.remote.nxt
 
inputPort - Variable in class lejos.remote.nxt.InputValues
 
inputStream - Variable in class lejos.hardware.device.UART
 
InputValues - Class in lejos.remote.nxt
Sensor input values for a remote NXT accessed via LCP.
InputValues() - Constructor for class lejos.remote.nxt.InputValues
 
inReachedSet(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for findPath; check if aNode is in the set of reached nodes
INSANE_PACKET - Static variable in class lejos.remote.nxt.ErrorMessages
 
inside(int, int) - Method in class lejos.robotics.geometry.RectangleInt32
Deprecated.
inside(Point) - Method in class lejos.robotics.mapping.LineMap
Check if a point is within the mapped area
inside(Point) - Method in interface lejos.robotics.mapping.RangeMap
Test if a point is within the mapped area
installDefaultMacros() - Method in class lejos.hardware.device.PFLink
Installs the macro definitions used by this class.
installMacro(int, byte[]) - Method in class lejos.hardware.device.PFLink
Installs a macro into the NRLink You really should call this only once for a new NRLink since it stores them in EEPROM even if turned of.
INSUFFICIENT_MEMORY_AVAILABLE - Static variable in class lejos.remote.nxt.ErrorMessages
 
intData - Variable in class lejos.remote.ev3.EV3Request
 
Integration - Class in lejos.utility
Integrate sensor measurement over time, e.g.
Integration(double, double) - Constructor for class lejos.utility.Integration
Create the integration object with the initial value for the integral value and the initial reading.
IntegrationFilter - Class in lejos.robotics.filter
Integrates samples over time.
IntegrationFilter(SampleProvider) - Constructor for class lejos.robotics.filter.IntegrationFilter
 
intersects(double, double, double, double) - Method in class lejos.robotics.geometry.Line2D
 
intersects(Rectangle2D) - Method in class lejos.robotics.geometry.Line2D
 
intersects(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D
Test if this Rectangle2D intersects a rectangle defined by double coordinates
intersects(RectangleInt32) - Method in class lejos.robotics.geometry.RectangleInt32
Test if this rectangle intersects a specified rectangle
intersects(Rectangle2D) - Method in class lejos.robotics.geometry.RectangularShape
Test if this shape intersects a given Rectangle2D
intersects(double, double, double, double) - Method in interface lejos.robotics.geometry.Shape
Test if the shape intersects the rectangle with top left at (x,y), width w and height h.
intersects(Rectangle2D) - Method in interface lejos.robotics.geometry.Shape
Test if the shape intersects the Rectangle2D r
intersectsAt(Line) - Method in class lejos.robotics.geometry.Line
Calculate the point of intersection of two lines.
intersectsLine(double, double, double, double) - Method in class lejos.robotics.geometry.Line2D
Test if this line intersects a given line
intersectsLine(Line2D) - Method in class lejos.robotics.geometry.Line2D
Tests if this line intersects a given line
intersectsLine(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D
Test if this rectangle intersects a given line
intValue - Variable in class lejos.remote.ev3.EV3Request
 
intValue10 - Variable in class lejos.remote.ev3.EV3Request
 
intValue11 - Variable in class lejos.remote.ev3.EV3Request
 
intValue2 - Variable in class lejos.remote.ev3.EV3Request
 
intValue3 - Variable in class lejos.remote.ev3.EV3Request
 
intValue4 - Variable in class lejos.remote.ev3.EV3Request
 
intValue5 - Variable in class lejos.remote.ev3.EV3Request
 
intValue6 - Variable in class lejos.remote.ev3.EV3Request
 
intValue7 - Variable in class lejos.remote.ev3.EV3Request
 
intValue8 - Variable in class lejos.remote.ev3.EV3Request
 
intValue9 - Variable in class lejos.remote.ev3.EV3Request
 
INVALID_MODE - Static variable in class lejos.hardware.motor.BasicMotor
 
invalidReading() - Method in class lejos.robotics.RangeReading
Test if reading is invalid
inverse() - Method in class lejos.utility.Matrix
Matrix inverse or pseudoinverse
invert - Variable in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
invert(boolean) - Method in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
Inverts the motor direction
invert - Variable in class lejos.robotics.chassis.WheeledChassis.Modeler
 
invert(boolean) - Method in class lejos.robotics.chassis.WheeledChassis.Modeler
Inverts the motor direction
invertMotor(RegulatedMotor) - Static method in class lejos.robotics.MirrorMotor
Returns an inverted RegulatedMotor.
invertMotor(EncoderMotor) - Static method in class lejos.robotics.MirrorMotor
Returns an inverted EncoderMotor.
IOPort - Interface in lejos.hardware.port
Basic interface for EV3 sensor ports.
ipAddress - Variable in class lejos.robotics.filter.PublishedSource
 
IR_CHANNELS - Static variable in class lejos.hardware.sensor.EV3IRSensor
 
IR_PROX - Static variable in class lejos.hardware.sensor.EV3IRSensor
 
IR_REMOTE - Static variable in class lejos.hardware.sensor.EV3IRSensor
 
IR_SEEK - Static variable in class lejos.hardware.sensor.EV3IRSensor
 
IRLink - Class in lejos.hardware.device
Supports for HiTechnic NXT IRLink Sensor (NIL1046) IRLink.
IRLink(I2CPort) - Constructor for class lejos.hardware.device.IRLink
 
IRLink(Port) - Constructor for class lejos.hardware.device.IRLink
 
IRTransmitter - Interface in lejos.hardware.device
Interface for infra-red transmitters that can send bytes to an RCX
is - Variable in class lejos.remote.ev3.RemoteRequestPort
 
isAckAvailable() - Method in class lejos.remote.rcx.LLCHandler
Check if an Ack is available
isAckAvailable() - Method in class lejos.remote.rcx.PacketHandler
Check if an ack is available
isActive() - Method in class lejos.robotics.filter.SubscribedProvider
 
isAddress(String) - Static method in class lejos.remote.nxt.NXTCommDevice
Determine if a string contains a Bluetooth style address.
isBackward() - Method in class lejos.hardware.device.PFMateMotor
Determines if motor is moving backwards this is based on what the receiver has in its registers
isBatteryLow() - Method in class lejos.hardware.device.SensorMux
Method used to get if battery status is low.
isBlinkingEnabled() - Method in interface lejos.hardware.device.DLight
Queries the blinking mode of the dLight
isBlinkingEnabled(int) - Method in class lejos.hardware.device.DLights
Queries the blinking status of the dLight
isBlocked(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
isBusy() - Method in class lejos.robotics.localization.MCLPoseProvider
returns true if particle weights are being updated.
isCalibrated - Variable in class lejos.remote.nxt.InputValues
 
isConnected() - Method in class lejos.remote.nxt.LCPResponder
Checks whether there is an active connection
isDown() - Method in interface lejos.hardware.Key
 
isDown() - Method in class lejos.remote.ev3.RemoteKey
 
isDown() - Method in class lejos.remote.ev3.RemoteRequestKey
 
isDown() - Method in interface lejos.remote.ev3.RMIKey
 
isDown() - Method in class lejos.remote.ev3.RMIRemoteKey
 
isEmpty() - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
isEmpty() - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
isEmpty() - Method in class lejos.robotics.geometry.RectangleInt32
Test if the rectangle is empty
isEmpty() - Method in class lejos.robotics.geometry.RectangularShape
Test if the rectangular shape is empty
isEnabled() - Method in interface lejos.hardware.device.DLight
Queries the status of the dLight
isEnabled(int) - Method in class lejos.hardware.device.DLights
Queries the status of the dLight
isEnabled() - Method in class lejos.hardware.sensor.EV3UltrasonicSensor
Indicate that the sensor is enabled.
isEnabled() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
 
isEnabled() - Method in interface lejos.robotics.objectdetection.FeatureDetector
Indicates if automatic scanning mode and listener notification is currently enabled.
isEnabled() - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
isEnabled() - Method in class lejos.robotics.objectdetection.FusorDetector
 
isFalse() - Method in class lejos.robotics.filter.FilterTerminal
 
isFloodlightOn() - Method in class lejos.hardware.sensor.EV3ColorSensor
Checks if the floodlight is currently on.
isFloodlightOn() - Method in class lejos.hardware.sensor.NXTColorSensor
 
isFloodlightOn() - Method in class lejos.hardware.sensor.NXTLightSensor
 
isFloodlightOn() - Method in class lejos.hardware.sensor.RCXLightSensor
 
isFloodlightOn() - Method in interface lejos.robotics.LampController
Checks if the floodlight is currently on.
isFlt() - Method in class lejos.hardware.device.PFMateMotor
Determines if motor is floating this is based on what the receiver has in its registers
isForward() - Method in class lejos.hardware.device.PFMateMotor
Determines if motor is moving forward this is based on what the receiver has in its registers
isFree(int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
isHeadingRequired() - Method in class lejos.robotics.navigation.Waypoint
 
isLocal() - Method in interface lejos.hardware.Brick
Test whether the brick is a local one
isLocal() - Method in class lejos.hardware.ev3.LocalEV3
 
isLocal() - Method in class lejos.remote.ev3.RemoteEV3
 
isLocal() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
isLocal() - Method in class lejos.remote.nxt.RemoteNXT
 
isLongRange() - Method in class lejos.hardware.sensor.SumoEyesSensor
Returns the current range of the sensor.
isLost() - Method in class lejos.robotics.localization.MCLPoseProvider
returns lost status - all particles have very low probability weights
isMoving() - Method in class lejos.hardware.device.LMotor
Method to know if Servo is moving to a determinated angle
isMoving() - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Returns true if the actuator is in motion.
isMoving() - Method in class lejos.hardware.device.MMXMotor
Return true if the motor is moving.
isMoving() - Method in class lejos.hardware.device.PFMateMotor
 
isMoving() - Method in class lejos.hardware.device.tetrix.TetrixMotor
Return true if the motor is moving.
isMoving() - Method in class lejos.hardware.device.tetrix.TetrixServoController
Returns whether or not there are servos on this controller that are moving.
isMoving() - Method in class lejos.hardware.motor.BaseRegulatedMotor
This method returns true if the motor is attempting to rotate.
isMoving() - Method in class lejos.hardware.motor.BasicMotor
Returns true iff the motor is in motion.
isMoving() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
isMoving() - Method in interface lejos.hardware.motor.MotorRegulator
Return true if the motor is currently active
isMoving() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
isMoving() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
isMoving() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
 
isMoving() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
isMoving() - Method in interface lejos.robotics.BaseMotor
Return true if the motor is moving.
isMoving() - Method in interface lejos.robotics.chassis.Chassis
Returns true if the robot is moving.
isMoving() - Method in class lejos.robotics.chassis.WheeledChassis
 
isMoving() - Method in interface lejos.robotics.LinearActuator
Return true if the actuator is in motion due to a move() or moveTo() order.
isMoving() - Method in class lejos.robotics.MirrorMotor
 
isMoving() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
isMoving() - Method in class lejos.robotics.navigation.Move
Test if move was in progress
isMoving() - Method in interface lejos.robotics.navigation.MoveController
true if the robot is moving
isMoving() - Method in class lejos.robotics.navigation.MovePilot
 
isMoving() - Method in class lejos.robotics.navigation.Navigator
Returns true if the robot is moving toward a waypoint.
isMoving() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
isMoving() - Method in class lejos.robotics.navigation.SteeringPilot
 
isNewSampleAvailable() - Method in class lejos.robotics.filter.SampleThread
 
isNonsingular() - Method in class lejos.utility.LUDecomposition
Is the matrix nonsingular?
isNumeric(String) - Method in class lejos.hardware.gps.NMEASentence
 
isOccupied(int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
isOpen() - Method in class lejos.remote.nxt.NXTCommand
Test is connection is open
isPacketAvailable() - Method in class lejos.remote.rcx.LLCHandler
Check if a packet is available
isPacketAvailable() - Method in class lejos.remote.rcx.LLCReliableHandler
Check if a packet is available.
isPacketAvailable() - Method in class lejos.remote.rcx.PacketHandler
Check if a packet is available
isPacketAvailable() - Static method in class lejos.remote.rcx.Serial
Test if a packet is available
isPowerOn() - Static method in class lejos.hardware.LocalBTDevice
Check to see if the device is currently powered on
isPressed(int) - Method in class lejos.hardware.device.SensorMux
Method used to manage a Touch Sensor
isPressed() - Method in interface lejos.robotics.Touch
Check if the sensor is pressed.
isPressed() - Method in class lejos.robotics.TouchAdapter
 
isSendError() - Static method in class lejos.remote.rcx.LLC
Return the error status of the last send
isSending() - Static method in class lejos.remote.rcx.LLC
Indicate whether the last send is still active
isStalled() - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Returns true if a move() or moveTo() order ended due to a motor stall.
isStalled() - Method in class lejos.hardware.device.MMXRegulatedMotor
 
isStalled() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
NOT IMPLEMENTED as the TEXTRIX motor controller does not support this command.
isStalled() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Return true if the motor is currently stalled.
isStalled() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
isStalled() - Method in interface lejos.hardware.motor.MotorRegulator
Return true if the motor is currently stalled.
isStalled() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
isStalled() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
returns true if motor is stalled
isStalled() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
isStalled() - Method in interface lejos.robotics.chassis.Chassis
Returns true if at least one of the wheels is stalled
isStalled() - Method in class lejos.robotics.chassis.WheeledChassis
 
isStalled() - Method in interface lejos.robotics.LinearActuator
Returns true if a move() or moveTo() order ended due to a stalled motor.
isStalled() - Method in class lejos.robotics.MirrorMotor
 
isStalled() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
isStalled() - Method in interface lejos.robotics.RegulatedMotor
returns true if motor is stalled
isStop() - Method in class lejos.hardware.device.PFMateMotor
Determines if motor is stopped this is based on what the receiver has in its registers
isTracked() - Method in class lejos.hardware.gps.Satellite
Indicates if the GPS receiver is actively tracking this satellite and using it to fix the GPS location.
isTraveling() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
returns returns true if the robot is travelling for a specific distance;
isTrue() - Method in class lejos.robotics.filter.FilterTerminal
 
isUp() - Method in interface lejos.hardware.Key
 
isUp() - Method in class lejos.remote.ev3.RemoteKey
 
isUp() - Method in class lejos.remote.ev3.RemoteRequestKey
 
isUp() - Method in interface lejos.remote.ev3.RMIKey
 
isUp() - Method in class lejos.remote.ev3.RMIRemoteKey
 
isUpdated() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns update success flag

J

JavaMotorRegulator - Class in lejos.hardware.motor
Java based regulator regulate velocity; also stop motor at desired rotation angle.
JavaMotorRegulator(TachoMotorPort) - Constructor for class lejos.hardware.motor.JavaMotorRegulator
 
JavaMotorRegulator.Controller - Class in lejos.hardware.motor
This class provides a single thread that drives all of the motor regulation process.

K

KalmanFilter - Class in lejos.utility
Implementation of a Kalman filter using the Matrix class
KalmanFilter(Matrix, Matrix, Matrix, Matrix, Matrix) - Constructor for class lejos.utility.KalmanFilter
 
KEEP_ALIVE - Static variable in class lejos.remote.nxt.LCP
 
KEEP_ALIVE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
keepRunning - Variable in class lejos.robotics.subsumption.Arbitrator
 
Key - Interface in lejos.hardware
 
KEY_LEFTMOTOR - Static variable in class lejos.utility.PilotProps
 
KEY_PRESSED - Static variable in interface lejos.hardware.Key
 
KEY_PRESSED_AND_RELEASED - Static variable in interface lejos.hardware.Key
 
KEY_RELEASED - Static variable in interface lejos.hardware.Key
 
KEY_REVERSE - Static variable in class lejos.utility.PilotProps
 
KEY_RIGHTMOTOR - Static variable in class lejos.utility.PilotProps
 
KEY_TRACKWIDTH - Static variable in class lejos.utility.PilotProps
 
KEY_WHEELDIAMETER - Static variable in class lejos.utility.PilotProps
 
keyArray - Variable in class lejos.hardware.ev3.LocalEV3
 
KeyListener - Interface in lejos.hardware
 
keyPressed(Key) - Method in interface lejos.hardware.KeyListener
 
keyReleased(Key) - Method in interface lejos.hardware.KeyListener
 
keys - Static variable in class lejos.hardware.Button
 
keys - Variable in class lejos.hardware.ev3.LocalEV3
 
Keys - Interface in lejos.hardware
 

L

LampController - Interface in lejos.robotics
Interface for a light sensor that also includes a lamp (usually LED) to provide illumination.
lastMove - Variable in class lejos.robotics.mapping.NavigationModel
 
lastPlannedMove - Variable in class lejos.robotics.mapping.NavigationModel
 
latest - Variable in class lejos.robotics.filter.PublishFilter
 
LATITUDE - Static variable in class lejos.hardware.gps.NMEASentence
 
LCD - Class in lejos.hardware.lcd
Provide access to the EV3 LCD display
lcd - Variable in class lejos.utility.TextMenu
 
lcdManager - Variable in class lejos.hardware.ev3.LocalEV3
 
LCDOutputStream - Class in lejos.hardware.lcd
A simple output stream that implements console output.
LCDOutputStream(TextLCD) - Constructor for class lejos.hardware.lcd.LCDOutputStream
 
LCDOutputStream() - Constructor for class lejos.hardware.lcd.LCDOutputStream
 
LCP - Class in lejos.remote.nxt
Implements the Lego Communication Protocol, with some extensions for lejos NXJ.
LCP - Static variable in class lejos.remote.nxt.NXTConnection
Lego Communications Protocol (LCP) I/O mode.
lcpErrorToString(byte) - Static method in class lejos.remote.nxt.ErrorMessages
 
LCPException - Exception in lejos.remote.nxt
 
LCPException() - Constructor for exception lejos.remote.nxt.LCPException
 
LCPException(String) - Constructor for exception lejos.remote.nxt.LCPException
 
LCPException(byte) - Constructor for exception lejos.remote.nxt.LCPException
 
LCPException(String, Throwable) - Constructor for exception lejos.remote.nxt.LCPException
 
LCPMessageListener - Interface in lejos.remote.nxt
 
LCPResponder - Class in lejos.remote.nxt
Support for LCP commands
LCPResponder(NXTCommConnector) - Constructor for class lejos.remote.nxt.LCPResponder
Create a Responder using the provided connector The connector is used to create the listening connection used to accept remote commands.
LDCMotor - Class in lejos.hardware.device
LDCMotor, Lattebox DC Motor, is a abstraction to model any DCMotor connected to LSC, Lattebox Servo Controller.
LDCMotor(I2CPort, int, String, byte) - Constructor for class lejos.hardware.device.LDCMotor
Constructor
LDCMotor(I2CPort, int, String, byte, int, int, int, int) - Constructor for class lejos.hardware.device.LDCMotor
 
led - Variable in class lejos.hardware.ev3.LocalEV3
 
LED - Interface in lejos.hardware
 
LEDPattern(int) - Static method in class lejos.hardware.Button
 
LEFT - Static variable in class lejos.hardware.Button
The Left button.
left - Variable in class lejos.hardware.ev3.LocalEV3
 
LEFT - Static variable in interface lejos.hardware.Key
 
LEFT - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Position the anchor point of text and images to the left of the text or image.
LEFT - Static variable in class lejos.hardware.sensor.SumoEyesSensor
The Constant LEFT (1).
LEFT - Static variable in interface lejos.remote.ev3.RMIKey
 
leftOrth() - Method in class lejos.robotics.geometry.Point
calculate left orthogonal vector of this
LegacySensorPort - Interface in lejos.hardware.port
Abstraction for a port that supports legacy RCX sensors.
lejos.hardware - package lejos.hardware
EV3 hardware support
lejos.hardware.device - package lejos.hardware.device
Support for EV3 third-party devices
lejos.hardware.device.tetrix - package lejos.hardware.device.tetrix
HiTechnic Tetrix Motor and Servo controller support.
lejos.hardware.ev3 - package lejos.hardware.ev3
EV3 hardware access
lejos.hardware.gps - package lejos.hardware.gps
The lejos.hardware.gps package provides GPS parsing.
lejos.hardware.lcd - package lejos.hardware.lcd
Access to the EV3 LCD
lejos.hardware.motor - package lejos.hardware.motor
Access to the motors that the EV3 supports.
lejos.hardware.port - package lejos.hardware.port
Access to EV3 ports
lejos.hardware.sensor - package lejos.hardware.sensor
Access to all the sensors that are supported on the EV3.
lejos.hardware.video - package lejos.hardware.video
Access to video devices
lejos.remote.ev3 - package lejos.remote.ev3
Access to remove EV3s from an EV3 or a PC.
lejos.remote.nxt - package lejos.remote.nxt
Remote NXT access over Bluetooth
lejos.remote.rcx - package lejos.remote.rcx
Emulation of RCX communication classes
lejos.robotics - package lejos.robotics
Hardware abstraction interfaces for the robotics package.
lejos.robotics.chassis - package lejos.robotics.chassis
Modeling of wheeled vehicles
lejos.robotics.filter - package lejos.robotics.filter
Filters for sample providers.
lejos.robotics.geometry - package lejos.robotics.geometry
Geometric shape support for robotics using float co-ordinates
lejos.robotics.localization - package lejos.robotics.localization
Localization support
lejos.robotics.mapping - package lejos.robotics.mapping
Support for maps
lejos.robotics.navigation - package lejos.robotics.navigation
Navigation classes.
lejos.robotics.objectdetection - package lejos.robotics.objectdetection
Object detection classes.
lejos.robotics.pathfinding - package lejos.robotics.pathfinding
Path finding classes.
lejos.robotics.subsumption - package lejos.robotics.subsumption
Support for subsumption architecture.
lejos.utility - package lejos.utility
More utility classes
LEN_SETTING - Static variable in class lejos.hardware.Button
 
LEN_SETTING - Static variable in interface lejos.hardware.Keys
 
length() - Method in class lejos.robotics.geometry.Line
Return the length of the line
length() - Method in class lejos.robotics.geometry.Point
Returns the length of this vector
lengthen(float) - Method in class lejos.robotics.geometry.Line
Make this line longer by an amount delta at each end.
lengthenLines(float) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
lengthens all the lines in the map by delta at each end
lengthenLines(float) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
lengthens all the lines in the map by delta at each end
LIGHT_ACTIVE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
LIGHT_GRAY - Static variable in class lejos.robotics.Color
 
LIGHT_INACTIVE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
lightColor - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
LightDetector - Interface in lejos.robotics
A platform independent implementation for sensors that can detect white light levels.
LightDetectorAdaptor - Class in lejos.robotics
 
LightDetectorAdaptor(SampleProvider) - Constructor for class lejos.robotics.LightDetectorAdaptor
allocates a LightSensorAdaptor ; sets mode to Ambient Accepts as a parameter one of EV3ColorSensor, NXTColorSensor, or NXTLightSensor
LightScanner - Class in lejos.robotics
Software abstraction of a light sensor rotating in a horizontal plane, driven by a motor.
LightScanner(RegulatedMotor, LightDetector, int, int) - Constructor for class lejos.robotics.LightScanner
Specify the hardware for this object.
Line - Class in lejos.robotics.geometry
Represents a line and supports calculating the point of intersection of two line segments.
Line(float, float, float, float) - Constructor for class lejos.robotics.geometry.Line
 
Line2D - Class in lejos.robotics.geometry
An abstract class representing a line in two dimensional space
Line2D() - Constructor for class lejos.robotics.geometry.Line2D
This is an abstract class that cannot be instantiated: use Line2D.Float or Line2D.Double.
Line2D.Double - Class in lejos.robotics.geometry
A line in 2D space using float coordinates
Line2D.Float - Class in lejos.robotics.geometry
A line in 2D space using float coordinates
LINE_TRACKING - Static variable in class lejos.hardware.device.NXTCam
Used by setTrackingMode() to choose line tracking.
linearAcceleration - Variable in class lejos.robotics.chassis.WheeledChassis
 
LinearActuator - Interface in lejos.robotics
Interface that defines the minimal implementation for a Linear Actuator device.
LinearCalibrationFilter - Class in lejos.robotics.filter
This filter is used to calibrate sensors for offset and scale errors using linear interpolation.
LinearCalibrationFilter(SampleProvider, String) - Constructor for class lejos.robotics.filter.LinearCalibrationFilter
Construcor
LinearCalibrationFilter(SampleProvider) - Constructor for class lejos.robotics.filter.LinearCalibrationFilter
 
linearSpeed - Variable in class lejos.robotics.chassis.WheeledChassis
 
LineFollowingMoveController - Interface in lejos.robotics.navigation
 
LineMap - Class in lejos.robotics.mapping
A map of a room or other closed environment, represented by line segments
LineMap(Line[], Rectangle) - Constructor for class lejos.robotics.mapping.LineMap
Create a map from an array of line segments and a bounding rectangle
LineMap() - Constructor for class lejos.robotics.mapping.LineMap
Constructor to use when map will be loaded from a data stream
linesIntersect(double, double, double, double, double, double, double, double) - Static method in class lejos.robotics.geometry.Line2D
Test if one line intersects another line
linkStatus() - Method in class lejos.hardware.sensor.DexterGPSSensor
Return status of link to the GPS satellites LED on dGPS should light if satellite lock acquired
listener - Variable in class lejos.robotics.filter.PublishFilter
 
listener - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
ListenerCaller - Interface in lejos.hardware
Interface for calling calling lejos listeners.
LLC - Class in lejos.remote.rcx
Emulates RCX LLC class using the RCXLink class.
LLCHandler - Class in lejos.remote.rcx
Packet handler than implement the LLC packet protocol.
LLCHandler(I2CPort) - Constructor for class lejos.remote.rcx.LLCHandler
 
LLCReliableHandler - Class in lejos.remote.rcx
A Packet handler that guarantees reliable delivery using checksums, acks, and a single bit sequence number.
LLCReliableHandler(PacketHandler) - Constructor for class lejos.remote.rcx.LLCReliableHandler
 
LMotor - Class in lejos.hardware.device
Generic abstraction to manage RC Servos and DC Motor.
LMotor(I2CPort, int, String, byte) - Constructor for class lejos.hardware.device.LMotor
Constructor
LMotor(Port, int, String, byte) - Constructor for class lejos.hardware.device.LMotor
Constructor
LnrActrFirgelliNXT - Class in lejos.hardware.device
A Linear Actuator class that provides blocking and non-blocking move actions with stall detection.
LnrActrFirgelliNXT(EncoderMotor) - Constructor for class lejos.hardware.device.LnrActrFirgelliNXT
Create a LnrActrFirgelliNXT instance.
LnrActrFirgelliNXT(Port) - Constructor for class lejos.hardware.device.LnrActrFirgelliNXT
Convenience constructor that creates an instance of a NXTMotor using the specified motor port.
load() - Method in class lejos.hardware.device.LMotor
Load Servo located in a position X
load(String) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Loads calibration parameters from the file system.
loadAllServos() - Method in class lejos.hardware.device.LSC
Load all servos connected this this LSC
loadObject(DataInputStream) - Method in class lejos.robotics.localization.MCLParticleSet
Load serialized particles from a data input stream
loadObject(DataInputStream) - Method in class lejos.robotics.localization.MCLPoseProvider
Load serialized estimated pose from a data input stream
loadObject(DataInputStream) - Method in class lejos.robotics.mapping.LineMap
Load a map from a DataInputStream
loadObject(DataInputStream) - Method in class lejos.robotics.navigation.Move
 
loadObject(DataInputStream) - Method in class lejos.robotics.navigation.Pose
 
loadObject(DataInputStream) - Method in class lejos.robotics.navigation.Waypoint
 
loadObject(DataInputStream) - Method in class lejos.robotics.objectdetection.RangeFeature
 
loadObject(DataInputStream) - Method in class lejos.robotics.pathfinding.Path
 
loadObject(DataInputStream) - Method in class lejos.robotics.RangeReadings
Load the readings from a DataInputStream
loadObject(DataInputStream) - Method in interface lejos.robotics.Transmittable
 
loadPersistentValues() - Method in class lejos.utility.PilotProps
 
loadSettings() - Method in interface lejos.hardware.Audio
Load the current system settings associated with this class.
loadSettings() - Static method in class lejos.hardware.Sound
Load the current system settings associated with this class.
loadSettings() - Method in class lejos.remote.ev3.RemoteAudio
 
loadSettings() - Method in class lejos.remote.ev3.RemoteRequestAudio
 
loadSettings() - Method in interface lejos.remote.ev3.RMIAudio
Load the current system settings associated with this class.
loadSettings() - Method in class lejos.remote.ev3.RMIRemoteAudio
 
loadSettings() - Static method in class lejos.remote.nxt.NXTCommDevice
Load the current system settings associated with this class.
loadSettings() - Method in class lejos.remote.nxt.RemoteNXTAudio
 
LocalBTDevice - Class in lejos.hardware
 
LocalBTDevice() - Constructor for class lejos.hardware.LocalBTDevice
 
LocalEV3 - Class in lejos.hardware.ev3
This class represents the local instance of an EV3 device.
LocalWifiDevice - Class in lejos.hardware
 
locate() - Method in interface lejos.robotics.localization.BeaconLocator
This method performs a scan around the robot.
lock(int) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Deprecated.
The regulator will always try to hold position unless the motor is set into float mode using flt().
log(String) - Method in class lejos.robotics.mapping.EV3NavigationModel
Log a message
LONG_RANGE_IR - Static variable in class lejos.hardware.device.RCXLink
 
LONGITUDE - Static variable in class lejos.hardware.gps.NMEASentence
 
LOW - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
lowerHandler - Variable in class lejos.remote.rcx.PacketHandler
 
lowPassFilter - Variable in class lejos.robotics.filter.AbstractCalibrationFilter
 
LowPassFilter - Class in lejos.robotics.filter
Provides a low-pass filter for samples
LowPassFilter(SampleProvider, float) - Constructor for class lejos.robotics.filter.LowPassFilter
Constructor
LOWSPEED - Static variable in interface lejos.remote.nxt.NXTProtocol
 
LOWSPEED_9V - Static variable in interface lejos.remote.nxt.NXTProtocol
 
LS_GET_STATUS - Static variable in class lejos.remote.nxt.LCP
 
LS_GET_STATUS - Static variable in interface lejos.remote.nxt.NXTProtocol
 
LS_READ - Static variable in class lejos.remote.nxt.LCP
 
LS_READ - Static variable in interface lejos.remote.nxt.NXTProtocol
 
LS_WRITE - Static variable in class lejos.remote.nxt.LCP
 
LS_WRITE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
LSC - Class in lejos.hardware.device
This class has been defined to manage the device LSC, Lattebox Servo Controller which manage until 10 RC Servos / DC Motors
LSC(I2CPort, byte) - Constructor for class lejos.hardware.device.LSC
Constructor
LSC(Port, byte) - Constructor for class lejos.hardware.device.LSC
Constructor
LSC_position - Variable in class lejos.hardware.device.LMotor
 
LServo - Class in lejos.hardware.device
LServo, Lattebox Servo, is a abstraction to model any RC Servo (continous and non continous) plugged to LSC, Lattebox Servo Controller.
LServo(I2CPort, int, String, byte) - Constructor for class lejos.hardware.device.LServo
Constructor
LServo(I2CPort, int, String, byte, int, int) - Constructor for class lejos.hardware.device.LServo
Constructor with the feature to set min and max angle
LServo(I2CPort, int, String, byte, int, int, int) - Constructor for class lejos.hardware.device.LServo
Constructor with the feature to set min, max and init angle
LSGetStatus(byte) - Method in class lejos.remote.nxt.NXTCommand
Returns the status for an Inter-Integrated Circuit (I2C) sensor (the ultrasound sensor) via the Low Speed (LS) data port.
LSRead(byte) - Method in class lejos.remote.nxt.NXTCommand
Reads data from an Inter-Integrated Circuit (I2C) sensor (the ultrasound sensor) via the Low Speed (LS) data port.
LSWrite(byte, byte[], byte) - Method in class lejos.remote.nxt.NXTCommand
Used to request data from an Inter-Integrated Circuit (I2C) sensor (the ultrasound sensor) via the Low Speed (LS) data port.
LUDecomposition - Class in lejos.utility
LU Decomposition.
LUDecomposition(Matrix) - Constructor for class lejos.utility.LUDecomposition
LU Decomposition

M

MAG_DATA - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
MAGENTA - Static variable in class lejos.robotics.Color
 
magMode - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
makeLeftOrth() - Method in class lejos.robotics.geometry.Point
Turns this vector into its left-handed cartesian orthagonal
makeRightOrth() - Method in class lejos.robotics.geometry.Point
Turns this vector into its right-handed cartesian orthagonal
map - Variable in class lejos.robotics.mapping.NavigationModel
 
maskToString(int) - Static method in class lejos.hardware.device.MindSensorsNumPad
The lower 12 bits (Bits 0 to 11) are converted to a string containing 0 to 9, *, and # depending on whether which of bits are set.
master - Variable in class lejos.robotics.chassis.WheeledChassis
 
Matrix - Class in lejos.utility
Matrix implementation derived from the JAMA project
Matrix(int, int) - Constructor for class lejos.utility.Matrix
Construct an m-by-n matrix of zeros.
Matrix(int, int, double) - Constructor for class lejos.utility.Matrix
Construct an m-by-n constant matrix.
Matrix(double[][]) - Constructor for class lejos.utility.Matrix
Construct a matrix from a 2-D array.
Matrix(double[][], int, int) - Constructor for class lejos.utility.Matrix
Construct a matrix quickly without checking arguments.
Matrix(double[], int) - Constructor for class lejos.utility.Matrix
Construct a matrix from a one-dimensional packed array
max - Variable in class lejos.robotics.filter.AbstractCalibrationFilter
 
MAX_AGE - Static variable in class lejos.robotics.filter.PublishedSource
 
MAX_DEVICE_DATALENGTH - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
MAX_FILENAMELENGTH - Static variable in class lejos.remote.nxt.NXTCommand
 
MAX_IO - Static variable in interface lejos.hardware.port.I2CPort
Maximum read/write request length
MAX_PACKET_SIZE - Static variable in class lejos.robotics.filter.PublishedSource
 
MAX_POWER - Static variable in interface lejos.hardware.port.BasicMotorPort
Maximum power setting = 100%
MAX_RELIABLE_RANGE_READING - Variable in class lejos.robotics.FixedRangeScanner
 
MAX_RELIABLE_RANGE_READING - Variable in class lejos.robotics.RotatingRangeScanner
 
MAX_SAMPLE_MESSAGE_SIZE - Static variable in class lejos.robotics.filter.PublishedSource
 
MAX_SPEED_AT_9V - Variable in class lejos.hardware.motor.BaseRegulatedMotor
 
MAX_TYPE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
maxDistance - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
maxHeadingError - Variable in class lejos.robotics.navigation.Waypoint
 
MaximumFilter - Class in lejos.robotics.filter
This filter returns the maximum values found in the N most recent samples.
MaximumFilter(SampleProvider, int) - Constructor for class lejos.robotics.filter.MaximumFilter
 
maxIterations - Static variable in class lejos.robotics.localization.MCLParticleSet
 
maxPositionError - Variable in class lejos.robotics.navigation.Waypoint
 
MAXSPEED - Static variable in class lejos.robotics.chassis.WheeledChassis
 
mcl - Variable in class lejos.robotics.mapping.NavigationModel
 
MCLParticle - Class in lejos.robotics.localization
Represents a particle for the particle filtering algorithm.
MCLParticle(Pose) - Constructor for class lejos.robotics.localization.MCLParticle
Create a particle with a specific pose
MCLParticleSet - Class in lejos.robotics.localization
Represents a particle set for the particle filtering algorithm.
MCLParticleSet(RangeMap, int, int) - Constructor for class lejos.robotics.localization.MCLParticleSet
Create a set of particles randomly distributed within the given map.
MCLParticleSet(RangeMap, int, int, RangeReadings, float, float) - Constructor for class lejos.robotics.localization.MCLParticleSet
Generates a set of particles within the map that have a minimum weight as as calculated from the particle pose, the range readings and the map.
MCLParticleSet(RangeMap, int, Pose, float, float) - Constructor for class lejos.robotics.localization.MCLParticleSet
Generates a circular cloud of particles centered on initialPose with random normal radius and angle, and random normal heading.
MCLPoseProvider - Class in lejos.robotics.localization
Maintains an estimate of the robot pose using sensor data.
MCLPoseProvider(MoveProvider, RangeScanner, RangeMap, int, int) - Constructor for class lejos.robotics.localization.MCLPoseProvider
Allocates a new MCLPoseProvider.
MCLPoseProvider(RangeMap, int, int) - Constructor for class lejos.robotics.localization.MCLPoseProvider
Constructor for use on PC
MeanFilter - Class in lejos.robotics.filter
This filter returns the mean values found in the N most recent samples.
MeanFilter(SampleProvider, int) - Constructor for class lejos.robotics.filter.MeanFilter
 
MedianFilter - Class in lejos.robotics.filter
This filter returns the median value found in the N most recent samples.
MedianFilter(SampleProvider, int) - Constructor for class lejos.robotics.filter.MedianFilter
 
MEDIUM - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
Menu - Interface in lejos.remote.ev3
 
menuMajorVersion - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
menuMinorVersion - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
menuPatchLevel - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
MenuReply - Class in lejos.remote.ev3
 
MenuReply() - Constructor for class lejos.remote.ev3.MenuReply
 
MenuRequest - Class in lejos.remote.ev3
 
MenuRequest() - Constructor for class lejos.remote.ev3.MenuRequest
 
MenuRequest.Request - Enum in lejos.remote.ev3
 
menuRevision - Variable in class lejos.remote.nxt.NXJFirmwareInfo
 
MESSAGE_READ - Static variable in class lejos.remote.nxt.LCP
 
MESSAGE_READ - Static variable in interface lejos.remote.nxt.NXTProtocol
 
MESSAGE_WRITE - Static variable in class lejos.remote.nxt.LCP
 
MESSAGE_WRITE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
messageRead(byte, byte, boolean) - Method in class lejos.remote.nxt.NXTCommand
Read message.
messageReceived(byte, String) - Method in interface lejos.remote.nxt.LCPMessageListener
 
messageWrite(int, String) - Static method in class lejos.remote.nxt.LCP
Write a message to a remote inbox
messageWrite(byte[], byte) - Method in class lejos.remote.nxt.NXTCommand
Sends a message to an inbox on the NXT for storage(?) For future reference, message size must be capped at 59 for USB.
min - Variable in class lejos.robotics.filter.AbstractCalibrationFilter
 
MIN_TIME - Static variable in class lejos.hardware.device.DeviceIdentifier
 
MIN_TYPE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
MindsensorsAbsoluteIMU - Class in lejos.hardware.sensor
Mindsensors AbsoluteIMU
Sensor interface for the Mindsensors AbsoluteIMU family of sensors.
MindsensorsAbsoluteIMU(I2CPort, int) - Constructor for class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
MindsensorsAbsoluteIMU(I2CPort) - Constructor for class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
MindsensorsAbsoluteIMU(Port, int) - Constructor for class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
MindsensorsAbsoluteIMU(Port) - Constructor for class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
MindsensorsAbsoluteIMU.ShortSensorMode - Class in lejos.hardware.sensor
 
MindsensorsAccelerometer - Class in lejos.hardware.sensor
Mindsensors acceleration (tilt) sensor ACCL-Nx-v2/v3
The Mindsensors Accelerometer Sensor measures acceleration or tilt in three axes.
MindsensorsAccelerometer(I2CPort, int) - Constructor for class lejos.hardware.sensor.MindsensorsAccelerometer
Creates a SampleProvider for the Mindsensors ACCL-Nx
MindsensorsAccelerometer(I2CPort) - Constructor for class lejos.hardware.sensor.MindsensorsAccelerometer
Creates a SampleProvider for the Mindsensors ACCL-Nx
MindsensorsAccelerometer(Port, int) - Constructor for class lejos.hardware.sensor.MindsensorsAccelerometer
Creates a SampleProvider for the Mindsensors ACCL-Nx
MindsensorsAccelerometer(Port) - Constructor for class lejos.hardware.sensor.MindsensorsAccelerometer
Creates a SampleProvider for the Mindsensors ACCL-Nx
MindsensorsBTSense - Class in lejos.hardware.sensor
Support for the Mindsensors BTSense application
MindsensorsBTSense() - Constructor for class lejos.hardware.sensor.MindsensorsBTSense
Connection to the BTSense application and identify device as EV3
MindsensorsCompass - Class in lejos.hardware.sensor
MindSensor Compass sensor
Description

The code for this sensor has not been tested.

MindsensorsCompass(I2CPort, int) - Constructor for class lejos.hardware.sensor.MindsensorsCompass
Create a compass sensor object
MindsensorsCompass(I2CPort) - Constructor for class lejos.hardware.sensor.MindsensorsCompass
Create a compass sensor object
MindsensorsCompass(Port, int) - Constructor for class lejos.hardware.sensor.MindsensorsCompass
Create a compass sensor object
MindsensorsCompass(Port) - Constructor for class lejos.hardware.sensor.MindsensorsCompass
Create a compass sensor object
MindsensorsDistanceSensorV2 - Class in lejos.hardware.sensor
Mindsensors DIST-Nx series of Optical Distance Sensors, Version 2
Mindsensors DIST Sensor measure the distance to an object in front of the sensor using IR light
MindsensorsDistanceSensorV2(I2CPort) - Constructor for class lejos.hardware.sensor.MindsensorsDistanceSensorV2
 
MindsensorsDistanceSensorV2(I2CPort, int) - Constructor for class lejos.hardware.sensor.MindsensorsDistanceSensorV2
 
MindsensorsDistanceSensorV2(Port) - Constructor for class lejos.hardware.sensor.MindsensorsDistanceSensorV2
 
MindsensorsDistanceSensorV2(Port, int) - Constructor for class lejos.hardware.sensor.MindsensorsDistanceSensorV2
 
MindsensorsGlideWheelMRegulatedMotor - Class in lejos.hardware.motor
Abstraction for a Mindsensors Glidewheel-M equipped PF motor.
Note: These settings are for the "M" motor.
MindsensorsGlideWheelMRegulatedMotor(TachoMotorPort) - Constructor for class lejos.hardware.motor.MindsensorsGlideWheelMRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
MindsensorsGlideWheelMRegulatedMotor(Port) - Constructor for class lejos.hardware.motor.MindsensorsGlideWheelMRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
MindsensorsGlideWheelXLRegulatedMotor - Class in lejos.hardware.motor
Abstraction for a Mindsensors Glidewheel-M equipped PF motor.
Note: These settings are for the "XL" motor.
MindsensorsGlideWheelXLRegulatedMotor(TachoMotorPort) - Constructor for class lejos.hardware.motor.MindsensorsGlideWheelXLRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
MindsensorsGlideWheelXLRegulatedMotor(Port) - Constructor for class lejos.hardware.motor.MindsensorsGlideWheelXLRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
MindsensorsLightSensorArray - Class in lejos.hardware.sensor
MindSensors Light Senor Array
This sensor an array of 8 sensors with controlled light source, returning you values of the sensor readings.
MindsensorsLightSensorArray(I2CPort, int) - Constructor for class lejos.hardware.sensor.MindsensorsLightSensorArray
Constructor
MindsensorsLightSensorArray(I2CPort) - Constructor for class lejos.hardware.sensor.MindsensorsLightSensorArray
Constructor
MindsensorsLightSensorArray(Port, int) - Constructor for class lejos.hardware.sensor.MindsensorsLightSensorArray
Constructor
MindsensorsLightSensorArray(Port) - Constructor for class lejos.hardware.sensor.MindsensorsLightSensorArray
Constructor
MindsensorsLineLeader - Class in lejos.hardware.sensor
MindSensors Line Follower Sensor
This sensor an array of 8 sensors with controlled light source, returning you values of the sensor readings.
MindsensorsLineLeader(I2CPort, int) - Constructor for class lejos.hardware.sensor.MindsensorsLineLeader
Constructor
MindsensorsLineLeader(I2CPort) - Constructor for class lejos.hardware.sensor.MindsensorsLineLeader
Constructor
MindsensorsLineLeader(Port, int) - Constructor for class lejos.hardware.sensor.MindsensorsLineLeader
Constructor
MindsensorsLineLeader(Port) - Constructor for class lejos.hardware.sensor.MindsensorsLineLeader
Constructor
MindSensorsNumPad - Class in lejos.hardware.device
LeJOS driver for the Mindsensors NumericPad.
MindSensorsNumPad(I2CPort) - Constructor for class lejos.hardware.device.MindSensorsNumPad
Constructor for objects of the NumericPad of Mindsensors.
MindSensorsNumPad(Port) - Constructor for class lejos.hardware.device.MindSensorsNumPad
Constructor for objects of the NumericPad of Mindsensors.
MindSensorsPressureSensor - Class in lejos.hardware.sensor
MindSensors Pressure Sensor
This sensor measures pressures produced by LEGO Pneumatics systems and lot more!

The code for this sensor has not been tested.

MindSensorsPressureSensor(I2CPort) - Constructor for class lejos.hardware.sensor.MindSensorsPressureSensor
 
MindSensorsPressureSensor(Port) - Constructor for class lejos.hardware.sensor.MindSensorsPressureSensor
 
MinimumFilter - Class in lejos.robotics.filter
This filter returns the minimum values found in the N most recent samples.
MinimumFilter(SampleProvider, int) - Constructor for class lejos.robotics.filter.MinimumFilter
 
minus(Matrix) - Method in class lejos.utility.Matrix
C = A - B
minusEquals(Matrix) - Method in class lejos.utility.Matrix
A = A - B
MirrorMotor - Class in lejos.robotics
This class returns a motor that rotates in the reverse direction of a regular motor.
MMXMotor - Class in lejos.hardware.device
Abstraction to drive a basic encoder motor with the NXTMMX motor multiplexer.
MMXRegulatedMotor - Class in lejos.hardware.device
Abstraction to drive a regulated encoder motor with the NXTMMX motor multiplexer.
mode - Variable in class lejos.hardware.motor.BasicMotor
 
mode - Variable in class lejos.remote.nxt.OutputState
 
MODE_CONTINUOUS - Static variable in class lejos.hardware.sensor.NXTUltrasonicSensor
 
MODE_OFF - Static variable in class lejos.hardware.sensor.NXTUltrasonicSensor
 
MODE_PING - Static variable in class lejos.hardware.sensor.NXTUltrasonicSensor
 
MODE_RAW - Static variable in interface lejos.hardware.sensor.SensorConstants
 
MODE_REG - Static variable in class lejos.hardware.sensor.DexterIMUSensor.DexterIMUAccelerationSensor
 
Modeler(RegulatedMotor, double) - Constructor for class lejos.robotics.chassis.WheeledChassis.Modeler
Creates a modeler object to model a robot wheel
modelHolonomicWheel(RegulatedMotor, double) - Static method in class lejos.robotics.chassis.WheeledChassis
Provides a modeler object to model a Holonomic motorized wheel on the chassis
modelWheel(RegulatedMotor, double) - Static method in class lejos.robotics.chassis.WheeledChassis
Provides a modeler object to model a Holonomic motorized wheel on the chassis
MODEMASK - Static variable in interface lejos.remote.nxt.NXTProtocol
 
modes - Variable in class lejos.hardware.sensor.BaseSensor
 
MODULE_NOT_FOUND - Static variable in class lejos.remote.nxt.ErrorMessages
 
ModulusFilter - Class in lejos.robotics.filter
Simple filter that adjusts the sample to use a specified zero value mod a given value
ModulusFilter(SampleProvider, float[], float) - Constructor for class lejos.robotics.filter.ModulusFilter
 
Motor - Class in lejos.hardware.motor
Motor class contains 3 instances of regulated motors.
motor - Variable in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
motor - Variable in class lejos.robotics.chassis.WheeledChassis.Modeler
 
motor - Variable in class lejos.robotics.chassis.WheeledChassis
 
MOTOR_1 - Static variable in class lejos.hardware.device.tetrix.TetrixMotorController
Represents Motor 1 as indicated on the controller
MOTOR_2 - Static variable in class lejos.hardware.device.tetrix.TetrixMotorController
Represents Motor 2 as indicated on the controller
MOTOR_A_FORWARD - Static variable in class lejos.hardware.device.RCXLink
 
MOTOR_A_REVERSED - Static variable in class lejos.hardware.device.RCXLink
 
MOTOR_B_FORWARD - Static variable in class lejos.hardware.device.RCXLink
 
MOTOR_B_REVERSED - Static variable in class lejos.hardware.device.RCXLink
 
MOTOR_C_FORWARD - Static variable in class lejos.hardware.device.RCXLink
 
MOTOR_C_REVERSED - Static variable in class lejos.hardware.device.RCXLink
 
MOTOR_CH1_A_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH1_A_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH1_A_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH1_A_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH1_B_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH1_B_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH1_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH1_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_A_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_A_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_A_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_A_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_B_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_B_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH2_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_A_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_A_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_A_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_A_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_B_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_B_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH3_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_A_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_A_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_A_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_A_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_B_BRAKE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_B_FLOAT - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_B_FORWARD - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_CH4_B_REVERSE - Static variable in class lejos.hardware.device.PFLink
 
MOTOR_M1 - Static variable in class lejos.hardware.device.NXTMMX
Represents Motor 1 as indicated on the controller
MOTOR_M2 - Static variable in class lejos.hardware.device.NXTMMX
Represents Motor 2 as indicated on the controller
MOTOR_PORT - Static variable in class lejos.remote.ev3.RemotePort
 
MOTOR_PORT - Static variable in class lejos.remote.ev3.RemoteRequestPort
 
MOTOR_PORT - Static variable in class lejos.remote.nxt.RemoteNXTPort
 
MOTOR_RUN_STATE_IDLE - Static variable in interface lejos.remote.nxt.NXTProtocol
Output will be idle
MOTOR_RUN_STATE_RAMPDOWN - Static variable in interface lejos.remote.nxt.NXTProtocol
Output will ramp-down
MOTOR_RUN_STATE_RAMPUP - Static variable in interface lejos.remote.nxt.NXTProtocol
Output will ramp-up
MOTOR_RUN_STATE_RUNNING - Static variable in interface lejos.remote.nxt.NXTProtocol
Output will be running
MOTORON - Static variable in interface lejos.remote.nxt.NXTProtocol
Turn on the specified motor
MotorPort - Interface in lejos.hardware.port
Abstraction for an EV3 output port.
MotorRegulator - Interface in lejos.hardware.motor
Interface for motor regulation regulate velocity; also stop motor at desired rotation angle.
MOTORS - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
move(int, boolean) - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Causes the actuator to move distance in encoder ticks.
move(int, boolean) - Method in interface lejos.robotics.LinearActuator
The actuator should retract (negative distance value) or extend (positive distance value) in encoder ticks distance.
Move - Class in lejos.robotics.navigation
Models a movement performed by a pilot
Move(float, float, boolean) - Constructor for class lejos.robotics.navigation.Move
Create a movement object to record a movement made by a pilot.
Move(Move.MoveType, float, float, float, float, boolean) - Constructor for class lejos.robotics.navigation.Move
Create a movement object to record a movement made by a pilot.
Move(Move.MoveType, float, float, boolean) - Constructor for class lejos.robotics.navigation.Move
Create a movement object to record a movement made by a pilot.
Move(boolean, float, float) - Constructor for class lejos.robotics.navigation.Move
Alternate constructor that uses angle and turn radius instead.
Move.MoveType - Enum in lejos.robotics.navigation
The type of movement made in sufficient detail to allow errors in the movement to be modeled.
MoveController - Interface in lejos.robotics.navigation
 
MoveListener - Interface in lejos.robotics.navigation
Any class that wants to be updated automatically by a MoveProvider should implement this interface.
movementActive() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Called to indicate that the motors are now running and should be monitored for movement.
movementStart() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
called at start of a movement to inform the listeners that a movement has started.
MovePilot - Class in lejos.robotics.navigation
The Pilot class is a software abstraction of the Pilot mechanism of a robot.
MovePilot(double, double, RegulatedMotor, RegulatedMotor) - Constructor for class lejos.robotics.navigation.MovePilot
Deprecated.
MovePilot(double, double, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.MovePilot
Deprecated.
MovePilot(double, double, double, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.MovePilot
Deprecated.
MovePilot(Chassis) - Constructor for class lejos.robotics.navigation.MovePilot
Allocates a Pilot object.
MoveProvider - Interface in lejos.robotics.navigation
Should be implemented by a Pilot that provides a partial movement to a pose when requested.
moveStart() - Method in interface lejos.robotics.chassis.Chassis
Method used by the MovePilot to tell the chassis that a new move has started.
moveStart() - Method in class lejos.robotics.chassis.WheeledChassis
 
moveStarted(Move, MoveProvider) - Method in class lejos.robotics.localization.BeaconPoseProvider
 
moveStarted(Move, MoveProvider) - Method in class lejos.robotics.localization.MCLPoseProvider
Required by MoveListener interface; does nothing
moveStarted(Move, MoveProvider) - Method in class lejos.robotics.localization.OdometryPoseProvider
called by a MoveProvider when movement starts
moveStarted(Move, MoveProvider) - Method in class lejos.robotics.mapping.EV3NavigationModel
Called when the pilot starts a move
moveStarted(Move, MoveProvider) - Method in interface lejos.robotics.navigation.MoveListener
Called when a Move Provider starts a move
moveStopped(Move, MoveProvider) - Method in class lejos.robotics.localization.BeaconPoseProvider
 
moveStopped(Move, MoveProvider) - Method in class lejos.robotics.localization.MCLPoseProvider
Required by MoveListener interface.
moveStopped(Move, MoveProvider) - Method in class lejos.robotics.localization.OdometryPoseProvider
called by a MoveProvider when movement ends
moveStopped(Move, MoveProvider) - Method in class lejos.robotics.mapping.EV3NavigationModel
Called when a move stops
moveStopped(Move, MoveProvider) - Method in interface lejos.robotics.navigation.MoveListener
Called by the movement provider when a move stops
moveStraight(float, int) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
This method causes the robot to move in a direction while keeping the front of the robot pointed in the current direction it is facing.
moveTo(int, boolean) - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Causes the actuator to move to absolute position in encoder ticks.
moveTo(Point) - Method in class lejos.robotics.geometry.Point
Makes this a copy of the other point
moveTo(int, boolean) - Method in interface lejos.robotics.LinearActuator
The actuator should move to absolute position in encoder ticks.
moveUpdate(float) - Method in class lejos.robotics.navigation.Pose
Move the specified distance in the direction of current heading.
MSC - Class in lejos.hardware.device
This class has been designed to manage the device MSC8, Mindsensors NXT Servo which manages up to 8 RC Servos.
MSC(Port) - Constructor for class lejos.hardware.device.MSC
Constructor
MSC(I2CPort) - Constructor for class lejos.hardware.device.MSC
 
MSC8_VBATT - Static variable in class lejos.hardware.device.MSC
 
msDelay(long) - Static method in class lejos.utility.Delay
Wait for the specified number of milliseconds.
MServo - Class in lejos.hardware.device
MServo, is a abstraction to model any RC Servo (continuous and non continuous) plugged to
MServo(I2CPort, int) - Constructor for class lejos.hardware.device.MServo
The initial Constructor.
MServo(I2CPort, int, String) - Constructor for class lejos.hardware.device.MServo
The initial Constructor.
MServo(I2CPort, int, String, int, int) - Constructor for class lejos.hardware.device.MServo
Constructor with the feature to set min, max and init angle
multiply(float) - Method in class lejos.robotics.geometry.Point
Scalar multiplication
multiplyBy(float) - Method in class lejos.robotics.geometry.Point
scalar multiplication
my_motor - Variable in class lejos.robotics.navigation.Ballbot
 

N

name - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
name - Variable in class lejos.remote.ev3.EV3Reply
 
name - Variable in class lejos.remote.ev3.MenuRequest
 
name - Variable in class lejos.remote.ev3.RemotePort
 
name - Variable in class lejos.remote.ev3.RemoteRequestPort
 
NAME - Static variable in class lejos.remote.nxt.NXTCommDevice
 
name - Variable in class lejos.remote.nxt.RemoteNXTPort
 
name - Variable in class lejos.robotics.filter.PublishedSource
 
name - Variable in class lejos.robotics.filter.PublishFilter
 
NAME_LEN - Static variable in class lejos.remote.nxt.NXTCommDevice
 
names - Variable in class lejos.remote.ev3.EV3Reply
 
names - Variable in class lejos.remote.ev3.MenuReply
 
nameToString(byte[]) - Static method in class lejos.remote.nxt.NXTCommDevice
Return a string version of a device devName held as a byte array
NavEventListener - Interface in lejos.robotics.mapping
 
NavigationListener - Interface in lejos.robotics.navigation
Interface for informing listeners that a way point has been reached.
NavigationMesh - Interface in lejos.robotics.pathfinding
A navigation mesh is a set of nodes covering a map area which represent branching pathways for the vehicle to move from one location to another.
NavigationModel - Class in lejos.robotics.mapping
NavigationModel is an abstract class that has two implementations: NXTNavigationModel and PCNavigationModel.
NavigationModel() - Constructor for class lejos.robotics.mapping.NavigationModel
 
NavigationModel.NavEvent - Enum in lejos.robotics.mapping
Navigation events that are transmitted between the PC and the NXT (and vice versa).
navigator - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
Navigator - Class in lejos.robotics.navigation
This class controls a robot to traverse a Path, a sequence of Waypoints.
Navigator(MoveController) - Constructor for class lejos.robotics.navigation.Navigator
Allocates a Navigator object, using pilot that implements the ArcMoveController interface.
Navigator(MoveController, PoseProvider) - Constructor for class lejos.robotics.navigation.Navigator
Allocates a Navigator object using a pilot and a custom poseProvider, rather than the default OdometryPoseProvider.
neighbors() - Method in class lejos.robotics.pathfinding.Node
Indicates the number of neighbors (nodes connected to this node).
newDataAvailable() - Method in class lejos.hardware.sensor.DexterCompassSensor
Reads the new data ready bit of the status register of the sensor.
newMotorController() - Method in class lejos.hardware.device.tetrix.TetrixControllerFactory
Get the next available Tetrix Motor controller.
newMove(float, int, int, boolean, boolean) - Method in class lejos.hardware.motor.JavaMotorRegulator
Initiate a new move and optionally wait for it to complete.
newMove(float, int, int, boolean, boolean) - Method in interface lejos.hardware.motor.MotorRegulator
Initiate a new move and optionally wait for it to complete.
newServoController() - Method in class lejos.hardware.device.tetrix.TetrixControllerFactory
Get the next available Tetrix Servo controller.
NMEASentence - Class in lejos.hardware.gps
Class designed to manage all NMEA Sentence.
NMEASentence() - Constructor for class lejos.hardware.gps.NMEASentence
 
NO_ACTIVE_PROGRAM - Static variable in class lejos.remote.nxt.ErrorMessages
 
NO_DETECTION - Static variable in class lejos.hardware.sensor.SumoEyesSensor
The Constant NO_DETECTION (0).
NO_FREE_MEMORY_IN_COMMUNICATION_BUFFER - Static variable in class lejos.remote.nxt.ErrorMessages
 
NO_LIMIT - Static variable in class lejos.hardware.motor.BaseRegulatedMotor
 
NO_LIMIT - Static variable in interface lejos.hardware.motor.MotorRegulator
 
NO_LINEAR_SPACE - Static variable in class lejos.remote.nxt.ErrorMessages
 
NO_MORE_FILES - Static variable in class lejos.remote.nxt.ErrorMessages
 
NO_MORE_HANDLES - Static variable in class lejos.remote.nxt.ErrorMessages
 
NO_OF_SENSOR_TYPES - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NO_SENSOR - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NO_SORTING - Static variable in class lejos.hardware.device.NXTCam
Used by sortBy() to choose no sorting of detected objects.
NO_SPACE - Static variable in class lejos.remote.nxt.ErrorMessages
 
NO_WRITE_BUFFERS - Static variable in class lejos.remote.nxt.ErrorMessages
 
Node(Point) - Constructor for class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
Node(float, float) - Constructor for class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
Node - Class in lejos.robotics.pathfinding
This class represents a Node which can be connected to other neighboring nodes.
Node(float, float) - Constructor for class lejos.robotics.pathfinding.Node
Creates a new instance of a node.
Node(Point) - Constructor for class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
NodePathFinder - Class in lejos.robotics.pathfinding
This path finder class uses one of the common search algorithms (e.g.
NodePathFinder(SearchAlgorithm, NavigationMesh) - Constructor for class lejos.robotics.pathfinding.NodePathFinder
Instantiates a NodePathFinder object using a specified algorithm.
NONE - Static variable in class lejos.robotics.Color
 
NOOF_CHARS - Static variable in class lejos.hardware.lcd.LCD
 
norm1() - Method in class lejos.utility.Matrix
One norm
normalize(float) - Method in class lejos.hardware.sensor.AnalogSensor
Helper method.
normalize() - Method in class lejos.robotics.geometry.Point
Sets this vector's length to 1 unit while retaining direction
normalize(float) - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
normalizedADValue - Variable in class lejos.remote.nxt.InputValues
The normalized value from the Analog to Digital (AD) converter.
normF() - Method in class lejos.utility.Matrix
Frobenius norm
normInf() - Method in class lejos.utility.Matrix
Infinity norm
NOT_A_LINEAR_FILE - Static variable in class lejos.remote.nxt.ErrorMessages
 
NOT_IMPLEMENTED - Static variable in class lejos.remote.nxt.ErrorMessages
 
notifyListeners(NMEASentence) - Static method in class lejos.hardware.gps.SimpleGPS
 
notifyListeners(Feature) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
notifyListeners(Feature) - Method in class lejos.robotics.objectdetection.TouchFeatureDetector
 
NR_RANGE_LONG - Static variable in class lejos.hardware.device.PFLink
 
NR_RANGE_SHORT - Static variable in class lejos.hardware.device.PFLink
 
nsDelay(long) - Static method in class lejos.utility.Delay
Wait for the specified number of nanoseconds.
NUM_KEYS - Static variable in interface lejos.hardware.Keys
 
NUMBER_OF_SENSORS - Static variable in class lejos.hardware.device.TouchMUX
number of touch sensors supported by this device
numberOfSamplesInCalibration - Variable in class lejos.robotics.filter.AbstractCalibrationFilter
 
numParticles() - Method in class lejos.robotics.localization.MCLParticleSet
Return the number of particles in the set
numReadings - Variable in class lejos.robotics.mapping.NavigationModel
 
NXJ_DEFRAG - Static variable in class lejos.remote.nxt.LCP
 
NXJ_DEFRAG - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_DISCONNECT - Static variable in class lejos.remote.nxt.LCP
 
NXJ_DISCONNECT - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_GET_AUTO_RUN - Static variable in class lejos.remote.nxt.LCP
 
NXJ_GET_AUTO_RUN - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_GET_DEFAULT_PROGRAM - Static variable in class lejos.remote.nxt.LCP
 
NXJ_GET_DEFAULT_PROGRAM - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_GET_KEY_CLICK_VOLUME - Static variable in class lejos.remote.nxt.LCP
 
NXJ_GET_KEY_CLICK_VOLUME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_GET_SLEEP_TIME - Static variable in class lejos.remote.nxt.LCP
 
NXJ_GET_SLEEP_TIME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_GET_VERSION - Static variable in class lejos.remote.nxt.LCP
 
NXJ_GET_VERSION - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_GET_VOLUME - Static variable in class lejos.remote.nxt.LCP
 
NXJ_GET_VOLUME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_PACKET_MODE - Static variable in class lejos.remote.nxt.LCP
 
NXJ_PACKET_MODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_SET_AUTO_RUN - Static variable in class lejos.remote.nxt.LCP
 
NXJ_SET_AUTO_RUN - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_SET_DEFAULT_PROGRAM - Static variable in class lejos.remote.nxt.LCP
 
NXJ_SET_DEFAULT_PROGRAM - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_SET_KEY_CLICK_VOLUME - Static variable in class lejos.remote.nxt.LCP
 
NXJ_SET_KEY_CLICK_VOLUME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_SET_SLEEP_TIME - Static variable in class lejos.remote.nxt.LCP
 
NXJ_SET_SLEEP_TIME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJ_SET_VOLUME - Static variable in class lejos.remote.nxt.LCP
 
NXJ_SET_VOLUME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
NXJFirmwareInfo - Class in lejos.remote.nxt
Information about leJOS NXJ firmware and menu
NXJFirmwareInfo() - Constructor for class lejos.remote.nxt.NXJFirmwareInfo
 
NXT - Interface in lejos.remote.nxt
 
NXT_ADC_RES - Static variable in interface lejos.hardware.sensor.SensorConstants
MAX value returned as a RAW sensor reading for standard NXT A/D sensors
NXTCam - Class in lejos.hardware.device
Mindsensors NXTCam.
NXTCam(I2CPort, int) - Constructor for class lejos.hardware.device.NXTCam
 
NXTCam(I2CPort) - Constructor for class lejos.hardware.device.NXTCam
 
NXTCam(Port, int) - Constructor for class lejos.hardware.device.NXTCam
 
NXTCam(Port) - Constructor for class lejos.hardware.device.NXTCam
 
NXTColorSensor - Class in lejos.hardware.sensor
LEGO NXT Color Sensor
allows the reading of raw color values.
NXTColorSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.NXTColorSensor
Create a new Color Sensor instance and bind it to a port.
NXTColorSensor(Port) - Constructor for class lejos.hardware.sensor.NXTColorSensor
Create a new Color Sensor instance and bind it to a port.
NXTComm - Class in lejos.remote.nxt
Initiates communication to a remote NXT.
NXTCommand - Class in lejos.remote.nxt
Sends LCP requests to the NXT and receives replies.
NXTCommand(NXTCommRequest) - Constructor for class lejos.remote.nxt.NXTCommand
Create a NXTCommand object.
nxtCommand - Variable in class lejos.remote.nxt.RemoteNXTIOPort
 
nxtCommand - Variable in class lejos.remote.nxt.RemoteNXTPort
 
NXTCommConnector - Class in lejos.remote.nxt
Standard interface to connect/wait for a connection.
NXTCommConnector() - Constructor for class lejos.remote.nxt.NXTCommConnector
 
NXTCommDevice - Class in lejos.remote.nxt
Base class for nxt communications devices.
NXTCommDevice() - Constructor for class lejos.remote.nxt.NXTCommDevice
 
NXTCommRequest - Interface in lejos.remote.nxt
Interface that all NXTComm implementation classes must implement for low-level communication with the NXT.
NXTConnection - Class in lejos.remote.nxt
 
NXTConnection() - Constructor for class lejos.remote.nxt.NXTConnection
 
NXTe - Class in lejos.hardware.device
Abstraction for a Lattebox NXT Extension Kit with Lattebox 10-Axis Servo Kit http://www.lattebox.com UML: http://www.juanantonio.info/p_research/robotics/lejos/nxj/lattebox/LatteboxNXTeKit.png
NXTe(I2CPort) - Constructor for class lejos.hardware.device.NXTe
Constructor
NXTe(Port) - Constructor for class lejos.hardware.device.NXTe
 
NXTE_ADDRESS - Static variable in class lejos.hardware.device.NXTe
 
NXTInputStream - Class in lejos.remote.nxt
Extends InputStream for BlueTooth; implements available()
NXTLightSensor - Class in lejos.hardware.sensor
LEGO NXT light Sensor
The NXT light sensor measures light levels of reflected or ambient light.
NXTLightSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.NXTLightSensor
Create a light sensor object attached to the specified port.
NXTLightSensor(Port) - Constructor for class lejos.hardware.sensor.NXTLightSensor
Create a light sensor object attached to the specified port.
NXTMMX - Class in lejos.hardware.device
Supports the Mindsensors NXTMMX motor multiplexor.
NXTMMX(I2CPort) - Constructor for class lejos.hardware.device.NXTMMX
Constructor for the NXTMMX
NXTMMX(Port) - Constructor for class lejos.hardware.device.NXTMMX
Constructor for the NXTMMX
NXTMMX(I2CPort, int) - Constructor for class lejos.hardware.device.NXTMMX
Constructor for the NXTMMX
NXTMMX(Port, int) - Constructor for class lejos.hardware.device.NXTMMX
Constructor for the NXTMMX
NXTname - Variable in class lejos.remote.nxt.DeviceInfo
 
nxtName - Variable in class lejos.robotics.mapping.NavigationModel
 
NXTOutputStream - Class in lejos.remote.nxt
Implements an OutputStream over NXT connections.
NXTProtocol - Interface in lejos.remote.nxt
LEGO Communication Protocol constants.
NXTRawIntValue(float) - Method in class lejos.hardware.sensor.AnalogSensor
Return the equivalent NXT RAW sensor reading to the given voltage
NXTRawValue(float) - Method in class lejos.hardware.sensor.AnalogSensor
Return the equivalent NXT RAW sensor reading to the given voltage
NXTRegulatedMotor - Class in lejos.hardware.motor
Abstraction for a Lego NXT motor.
NXTRegulatedMotor(TachoMotorPort) - Constructor for class lejos.hardware.motor.NXTRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
NXTRegulatedMotor(Port) - Constructor for class lejos.hardware.motor.NXTRegulatedMotor
Use this constructor to assign a variable of type motor connected to a particular port.
NXTSERVO_ADDRESS - Static variable in class lejos.hardware.device.MSC
 
NXTSoundSensor - Class in lejos.hardware.sensor
NXT Sound sensor
Description
NXTSoundSensor(Port) - Constructor for class lejos.hardware.sensor.NXTSoundSensor
Create a sound sensor.
NXTSoundSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.NXTSoundSensor
Create a sound sensor.
NXTSoundSensor.DBMode - Class in lejos.hardware.sensor
 
NXTTouchSensor - Class in lejos.hardware.sensor
NXT Touch sensor
A sensor that can be pressed like a button.
NXTTouchSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.NXTTouchSensor
Create a touch sensor object attached to the specified open port.
NXTTouchSensor(Port) - Constructor for class lejos.hardware.sensor.NXTTouchSensor
Create an NXT touch sensor object attached to the specified port.
NXTUltrasonicSensor - Class in lejos.hardware.sensor
NXT Ultrasonic sensor
The NXT Ultrasonic sensor generates sound waves and reads their echoes to detect and measure distance from objects.
NXTUltrasonicSensor(I2CPort) - Constructor for class lejos.hardware.sensor.NXTUltrasonicSensor
 
NXTUltrasonicSensor(Port) - Constructor for class lejos.hardware.sensor.NXTUltrasonicSensor
 
NXTUltrasonicSensor.DistanceMode - Class in lejos.hardware.sensor
 
NXTUltrasonicSensor.PingMode - Class in lejos.hardware.sensor
 

O

OBJECT_TRACKING - Static variable in class lejos.hardware.device.NXTCam
Used by setTrackingMode() to choose object tracking.
OccupancyGridMap - Class in lejos.robotics.mapping
 
OccupancyGridMap(int, int, double, double, double) - Constructor for class lejos.robotics.mapping.OccupancyGridMap
 
odometer - Variable in class lejos.robotics.chassis.WheeledChassis
 
OdometryPoseProvider - Class in lejos.robotics.localization
A PoseProvider keeps track of the robot Pose.
OdometryPoseProvider(MoveProvider) - Constructor for class lejos.robotics.localization.OdometryPoseProvider
Allocates a new OdometryPoseProivder and registers it with the MovePovider as a listener.
offset - Variable in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
offset - Variable in class lejos.robotics.chassis.WheeledChassis.Modeler
 
offset(double) - Method in class lejos.robotics.chassis.WheeledChassis.Modeler
Defines the offset off the wheel
OFFSET_AND_SCALE_CALIBRATION - Static variable in class lejos.robotics.filter.LinearCalibrationFilter
 
OFFSET_CALIBRATION - Static variable in class lejos.robotics.filter.LinearCalibrationFilter
 
OffsetCorrectionFilter - Class in lejos.robotics.filter
The OffsetCorrectionFilter is used to correct sensors that have an unknown offset error.
The offset error is calculated by this class and then substracted from the sample to give a corrected sample.
OffsetCorrectionFilter(SampleProvider) - Constructor for class lejos.robotics.filter.OffsetCorrectionFilter
Constructor for the offset correction filter using default parameters.
OffsetCorrectionFilter(SampleProvider, float[]) - Constructor for class lejos.robotics.filter.OffsetCorrectionFilter
Constructor for the offset correction filter using default window of 200 samples.
OffsetCorrectionFilter(SampleProvider, float[], int) - Constructor for class lejos.robotics.filter.OffsetCorrectionFilter
Constructor for the offset correction filter.
Constructor
OmniPilot - Class in lejos.robotics.navigation
Deprecated.
use MovePilot instead.
OmniPilot(float, float, RegulatedMotor, RegulatedMotor, RegulatedMotor, boolean, boolean, Power) - Constructor for class lejos.robotics.navigation.OmniPilot
Deprecated.
Instantiates a new omnidirectional pilot.
OmniPilot(float, float, RegulatedMotor, RegulatedMotor, RegulatedMotor, boolean, boolean, Power, Gyroscope) - Constructor for class lejos.robotics.navigation.OmniPilot
Deprecated.
Instantiates a new omnidirectional pilot.
ONE_ROTATION - Static variable in class lejos.hardware.sensor.RCXRotationSensor
The incremental count for one whole rotation (360 degrees).
Opcode - Interface in lejos.remote.rcx
Opcode constants.
OPCODE_ABSOLUTE_VALUE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_ABSOLUTE_VALUE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_ADD_TO_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_ADD_TO_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_ALIVE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_ALIVE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_AND_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_AND_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_BRANCH_ALWAYS_FAR - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_BRANCH_ALWAYS_NEAR - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_CALL_SUBROUTINE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_CLEAR_MESSAGE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_CLEAR_SENSOR_VALUE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_CLEAR_SENSOR_VALUE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_CLEAR_TIMER - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_CLEAR_TIMER_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DATALOG_NEXT - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DATALOG_NEXT_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DECREMENT_LOOP_COUNTER_FAR - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DECREMENT_LOOP_COUNTER_NEAR - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_ALL_SUBROUTINES - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_ALL_SUBROUTINES_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_ALL_TASKS - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_ALL_TASKS_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_FIRMWARE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_FIRMWARE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_SUBROUTINE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_SUBROUTINE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_TASK - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DELETE_TASK_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DIVIDE_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_DIVIDE_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_BATTERY_POWER - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_BATTERY_POWER_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_MEMORY_MAP - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_MEMORY_MAP_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_VALUE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_VALUE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_VERSIONS - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_GET_VERSIONS_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_MASK - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_MULTIPLY_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_MULTIPLY_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_OR_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_OR_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_PLAY_SOUND_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_PLAY_TONE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_PLAY_TONE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_POWER_OFF - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_POWER_OFF_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_REMOTE_COMMAND - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SEND_MESSAGE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_DATALOG_SIZE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_DATALOG_SIZE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_DISPLAY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_DISPLAY_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_LOOP_COUNTER - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_MESSAGE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_MOTOR_DIRECTION - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_MOTOR_DIRECTION_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_MOTOR_ON_OFF - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_MOTOR_ON_OFF_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_MOTOR_POWER - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_MOTOR_POWER_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_POWER_DOWN_DELAY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_POWER_DOWN_DELAY_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_PROGRAM_NUMBER - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_PROGRAM_NUMBER_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_SENSOR_MODE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_SENSOR_MODE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_SENSOR_TYPE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_SENSOR_TYPE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_TIME - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_TIME_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_TRANSMITTER_RANGE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_TRANSMITTER_RANGE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SET_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SIGN_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SIGN_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_FIRMWARE_DOWNLOAD - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_FIRMWARE_DOWNLOAD_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_SUBROUTINE_DOWNLOAD - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_SUBROUTINE_DOWNLOAD_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_TASK - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_TASK_DOWNLOAD - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_TASK_DOWNLOAD_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_START_TASK_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_STOP_ALL_TASKS - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_STOP_ALL_TASKS_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_STOP_TASK - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_STOP_TASK_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SUBTRACT_FROM_VARIABLE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_SUBTRACT_FROM_VARIABLE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_TEST_AND_BRANCH_FAR - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_TEST_AND_BRANCH_NEAR - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_TRANSFER_DATA - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_TRANSFER_DATA_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_UNLOCK_FIRMWARE - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_UNLOCK_FIRMWARE_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_UPLOAD_DATALOG - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_UPLOAD_DATALOG_REPLY - Static variable in interface lejos.remote.rcx.Opcode
 
OPCODE_WAIT - Static variable in interface lejos.remote.rcx.Opcode
 
open(Class<T>) - Method in interface lejos.hardware.port.Port
Obtain access to a class that can be used to talk to the port hardware
open(int, int, int, int, int) - Method in interface lejos.hardware.video.Video
Open the device and make it available for use, specify the desired frame size.
open(int, int) - Method in interface lejos.hardware.video.Video
Open the device and make it available for use, specify the desired frame size.
open(int, int, RemotePort) - Method in class lejos.remote.ev3.RemoteAnalogPort
 
open(int, int, RemotePort) - Method in class lejos.remote.ev3.RemoteI2CPort
 
open(int, int, RemotePort) - Method in class lejos.remote.ev3.RemoteIOPort
 
open(int, int, RemotePort) - Method in class lejos.remote.ev3.RemoteMotorPort
 
open(Class<T>) - Method in class lejos.remote.ev3.RemotePort
Obtain access to a class that can be used to talk to the port hardware
open(int, int, RemoteRequestPort) - Method in class lejos.remote.ev3.RemoteRequestAnalogPort
 
open(int, int, RemoteRequestPort) - Method in class lejos.remote.ev3.RemoteRequestI2CPort
 
open(int, int, RemoteRequestPort) - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
open(int, int, RemoteRequestPort) - Method in class lejos.remote.ev3.RemoteRequestMotorPort
 
open(Class<T>) - Method in class lejos.remote.ev3.RemoteRequestPort
 
open(int, int, RemoteRequestPort) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
open(int, int, RemotePort) - Method in class lejos.remote.ev3.RemoteUARTPort
 
open(String, int) - Method in class lejos.remote.nxt.NXTComm
 
open(int, int, RemoteNXTPort) - Method in class lejos.remote.nxt.RemoteNXTI2CPort
allow access to the specified port
open(int, int, RemoteNXTPort) - Method in class lejos.remote.nxt.RemoteNXTIOPort
Open the sensor port.
open(Class<T>) - Method in class lejos.remote.nxt.RemoteNXTPort
Obtain access to a class that can be used to talk to the port hardware
open(byte, byte) - Method in class lejos.remote.rcx.PacketHandler
Set the source and destination for this connection.
open(String) - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
OPEN_APPEND_DATA - Static variable in class lejos.remote.nxt.LCP
 
OPEN_APPEND_DATA - Static variable in interface lejos.remote.nxt.NXTProtocol
 
OPEN_READ - Static variable in class lejos.remote.nxt.LCP
 
OPEN_READ - Static variable in interface lejos.remote.nxt.NXTProtocol
 
OPEN_READ_LINEAR - Static variable in class lejos.remote.nxt.LCP
 
OPEN_READ_LINEAR - Static variable in interface lejos.remote.nxt.NXTProtocol
 
OPEN_WRITE - Static variable in class lejos.remote.nxt.LCP
 
OPEN_WRITE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
OPEN_WRITE_DATA - Static variable in class lejos.remote.nxt.LCP
 
OPEN_WRITE_DATA - Static variable in interface lejos.remote.nxt.NXTProtocol
 
OPEN_WRITE_LINEAR - Static variable in class lejos.remote.nxt.LCP
 
OPEN_WRITE_LINEAR - Static variable in interface lejos.remote.nxt.NXTProtocol
 
openAnalogPort(String) - Method in interface lejos.remote.ev3.RMIEV3
 
openAnalogPort(String) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
openConfigPort() - Method in class lejos.hardware.device.DeviceIdentifier
 
openDataInputStream() - Method in interface lejos.remote.nxt.InputConnection
Open and return a data input stream for a connection.
openDataInputStream() - Method in class lejos.remote.nxt.NXTConnection
 
openDataOutputStream() - Method in class lejos.remote.nxt.NXTConnection
 
openDataOutputStream() - Method in interface lejos.remote.nxt.OutputConnection
Open and return a data output stream for a connection.
openI2CPort(String) - Method in interface lejos.remote.ev3.RMIEV3
 
openI2CPort(String) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
openInputStream() - Method in interface lejos.remote.nxt.InputConnection
Open and return an input stream for a connection.
openInputStream() - Method in class lejos.remote.nxt.NXTConnection
 
openMotorPort(String) - Method in interface lejos.remote.ev3.RMIEV3
 
openMotorPort(String) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
openOutputStream() - Method in class lejos.remote.nxt.NXTConnection
 
openOutputStream() - Method in interface lejos.remote.nxt.OutputConnection
Open and return an output stream for a connection.
openPorts - Static variable in class lejos.remote.ev3.RemoteIOPort
 
openPorts - Static variable in class lejos.remote.ev3.RemoteRequestIOPort
 
openPorts - Static variable in class lejos.remote.nxt.RemoteNXTIOPort
 
openRead(String) - Method in class lejos.remote.nxt.NXTCommand
Opens a file on the NXT for reading.
openTime - Variable in class lejos.hardware.device.DeviceIdentifier
 
openUARTPort(String) - Method in interface lejos.remote.ev3.RMIEV3
 
openUARTPort(String) - Method in class lejos.remote.ev3.RMIRemoteEV3
 
openWrite(String, int) - Method in class lejos.remote.nxt.NXTCommand
Opens a file on the NXT for writing.
ORANGE - Static variable in class lejos.robotics.Color
 
os - Variable in class lejos.remote.ev3.RemoteRequestPort
 
OUT_BOTTOM - Static variable in class lejos.robotics.geometry.Rectangle2D
The bitmask that indicates that a point lies below this rectangle.
OUT_LEFT - Static variable in class lejos.robotics.geometry.Rectangle2D
The bitmask that indicates that a point lies to the left of this rectangle.
OUT_OF_BOUNDARY - Static variable in class lejos.remote.nxt.ErrorMessages
 
OUT_RIGHT - Static variable in class lejos.robotics.geometry.Rectangle2D
The bitmask that indicates that a point lies to the right of this rectangle.
OUT_TOP - Static variable in class lejos.robotics.geometry.Rectangle2D
The bitmask that indicates that a point lies above this rectangle.
outcode(double, double) - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
outcode(double, double) - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
outcode(Point2D) - Method in class lejos.robotics.geometry.Rectangle2D
Returns a mask value that specifies where a given point lies with respect to this rectangle.
outcode(double, double) - Method in class lejos.robotics.geometry.Rectangle2D
Returns a mask value that specifies where a point lies with respect to this rectangle.
outcode(double, double) - Method in class lejos.robotics.geometry.RectangleInt32
 
OutputConnection - Interface in lejos.remote.nxt
 
outputPort - Variable in class lejos.remote.nxt.OutputState
 
OutputState - Class in lejos.remote.nxt
Container for holding the output state values.
OutputState(int) - Constructor for class lejos.remote.nxt.OutputState
 
outputStream - Variable in class lejos.hardware.device.UART
 

P

PACKET - Static variable in class lejos.remote.nxt.NXTConnection
PACKET I/O mode.
PacketHandler - Class in lejos.remote.rcx
Abstract packet handler.
PacketHandler() - Constructor for class lejos.remote.rcx.PacketHandler
 
PacketHandler(PacketHandler) - Constructor for class lejos.remote.rcx.PacketHandler
 
packetHandler - Variable in class lejos.remote.rcx.RCXAbstractPort
 
parse(String) - Method in class lejos.hardware.gps.GGASentence
Method used to parse a GGA Sentence
parse(String) - Method in class lejos.hardware.gps.GSASentence
Method used to parse a GGA Sentence
parse(String) - Method in class lejos.hardware.gps.GSVSentence
Method used to parse a GSV Sentence
parse(String) - Method in class lejos.hardware.gps.NMEASentence
Abstract method to parse out all relevant data from the nmeaSentence.
parse(String) - Method in class lejos.hardware.gps.RMCSentence
Parse a RMC Sentence $GPRMC,081836,A,3751.65,S,14507.36,E,000.0,360.0,130998,011.3,E*62
parse(String) - Method in class lejos.hardware.gps.VTGSentence
Parse a RMC Sentence $GPVTG,054.7,T,034.4,M,005.5,N,010.2,K,A*53
particles - Variable in class lejos.robotics.mapping.NavigationModel
 
passivate() - Method in interface lejos.hardware.port.LegacySensorPort
 
path - Variable in class lejos.robotics.mapping.NavigationModel
 
Path - Class in lejos.robotics.pathfinding
Represents a path consisting of an ordered collection of waypoints
Path() - Constructor for class lejos.robotics.pathfinding.Path
 
pathComplete(Waypoint, Pose, int) - Method in class lejos.robotics.mapping.EV3NavigationModel
Called when a path has been completed
pathComplete(Waypoint, Pose, int) - Method in interface lejos.robotics.navigation.NavigationListener
Called when the robot has reached the last Waypoint of the path
pathCompleted() - Method in class lejos.robotics.navigation.Navigator
Returns true if the the final waypoint has been reached
PathFinder - Interface in lejos.robotics.pathfinding
This class creates a set of waypoints connected by straight lines that lead from one location to another without colliding with mapped geometry.
pathGenerated() - Method in class lejos.robotics.mapping.EV3NavigationModel
Called when a path finder has finished generating a path
pathGenerated() - Method in class lejos.robotics.navigation.Navigator
 
pathGenerated() - Method in interface lejos.robotics.navigation.WaypointListener
Called when generation of the path is complete
pathInterrupted(Waypoint, Pose, int) - Method in class lejos.robotics.mapping.EV3NavigationModel
Called when a path has been interrupted
pathInterrupted(Waypoint, Pose, int) - Method in interface lejos.robotics.navigation.NavigationListener
called when the robot has stopped, not at a Waypoint
pause(int) - Static method in class lejos.hardware.Sound
 
PCTFULLSCALEMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
PENDING_COMMUNICATION_TRANSACTION_IN_PROGRESS - Static variable in class lejos.remote.nxt.ErrorMessages
 
PERIODCOUNTERMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
PERSISTENT_FILENAME - Static variable in class lejos.utility.PilotProps
 
PF_BACKWARD - Static variable in class lejos.hardware.device.IRLink
 
PF_BRAKE - Static variable in class lejos.hardware.device.IRLink
 
PF_FLOAT - Static variable in class lejos.hardware.device.IRLink
 
PF_FORWARD - Static variable in class lejos.hardware.device.IRLink
 
PF_MODE_COMBO_DIRECT - Static variable in class lejos.hardware.device.IRLink
 
PFLink - Class in lejos.hardware.device
Class for controlling PF Motors with MindSensors NRLink-Nx
PFLink(I2CPort, int) - Constructor for class lejos.hardware.device.PFLink
 
PFLink(I2CPort) - Constructor for class lejos.hardware.device.PFLink
 
PFLink(Port, int) - Constructor for class lejos.hardware.device.PFLink
 
PFLink(Port) - Constructor for class lejos.hardware.device.PFLink
 
PFMate - Class in lejos.hardware.device
Supports Mindsensors PF Mate
This device is used to control Lego Power Function IR receiver
PFMate(I2CPort, int) - Constructor for class lejos.hardware.device.PFMate
Constructor takes in the sensor port and the PF channel you will be using
PFMate(I2CPort, int, int) - Constructor for class lejos.hardware.device.PFMate
Constructor takes in the sensor port and the PF channel you will be using
PFMate(Port, int) - Constructor for class lejos.hardware.device.PFMate
Constructor takes in the sensor port and the PF channel you will be using
PFMate(Port, int, int) - Constructor for class lejos.hardware.device.PFMate
Constructor takes in the sensor port and the PF channel you will be using
PFMateMotor - Class in lejos.hardware.device
Motor class for PFMate class
PFMotorPort - Class in lejos.hardware.device
MotorPort for PF Motors using HiTechnic IRLink
PFMotorPort(IRLink, int, int) - Constructor for class lejos.hardware.device.PFMotorPort
 
PIANO - Static variable in interface lejos.hardware.Sounds
 
pilot - Variable in class lejos.robotics.FixedRangeScanner
 
pilot - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
PilotProps - Class in lejos.utility
Configuration class for Differential Pilot.
PilotProps() - Constructor for class lejos.utility.PilotProps
 
ping() - Method in class lejos.hardware.device.RCXLink
 
PingMode() - Constructor for class lejos.hardware.sensor.NXTUltrasonicSensor.PingMode
 
PINK - Static variable in class lejos.robotics.Color
 
PIX_FMT_JPEG - Static variable in interface lejos.hardware.video.Video
 
PIX_FMT_MJPEG - Static variable in interface lejos.hardware.video.Video
 
PIX_FMT_YUYV - Static variable in interface lejos.hardware.video.Video
 
PLAY_SOUND_FILE - Static variable in class lejos.remote.nxt.LCP
 
PLAY_SOUND_FILE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
PLAY_TONE - Static variable in class lejos.remote.nxt.LCP
 
PLAY_TONE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
playNote(int[], int, int) - Method in interface lejos.hardware.Audio
Play a note with attack, decay, sustain and release shape.
playNote(int[], int, int) - Static method in class lejos.hardware.Sound
Play a note with attack, decay, sustain and release shape, which is known as a ADSR envelope.
playNote(int[], int, int) - Method in class lejos.remote.ev3.RemoteAudio
 
playNote(int[], int, int) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
playNote(int[], int, int) - Method in interface lejos.remote.ev3.RMIAudio
Play a note with attack, decay, sustain and release shape.
playNote(int[], int, int) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
playNote(int[], int, int) - Method in class lejos.remote.nxt.RemoteNXTAudio
 
playSample(File, int) - Method in interface lejos.hardware.Audio
Play a wav file
playSample(File) - Method in interface lejos.hardware.Audio
Play a wav file
playSample(byte[], int, int, int, int) - Method in interface lejos.hardware.Audio
Queue a series of PCM samples to play at the specified volume and sample rate.
playSample(File, int) - Static method in class lejos.hardware.Sound
Play a wav file.
playSample(File) - Static method in class lejos.hardware.Sound
Play a wav file.
playSample(byte[], int, int, int, int) - Static method in class lejos.hardware.Sound
Queue a series of PCM samples to play at the specified volume and sample rate.
playSample(File, int) - Method in class lejos.remote.ev3.RemoteAudio
 
playSample(File) - Method in class lejos.remote.ev3.RemoteAudio
 
playSample(byte[], int, int, int, int) - Method in class lejos.remote.ev3.RemoteAudio
 
playSample(File, int) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
playSample(File) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
playSample(byte[], int, int, int, int) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
playSample(File, int) - Method in interface lejos.remote.ev3.RMIAudio
Play a wav file
playSample(File) - Method in interface lejos.remote.ev3.RMIAudio
Play a wav file
playSample(byte[], int, int, int, int) - Method in interface lejos.remote.ev3.RMIAudio
Queue a series of PCM samples to play at the specified volume and sample rate.
playSample(File, int) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
playSample(File) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
playSample(byte[], int, int, int, int) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
playSample(File, int) - Method in class lejos.remote.nxt.RemoteNXTAudio
 
playSample(File) - Method in class lejos.remote.nxt.RemoteNXTAudio
 
playSample(byte[], int, int, int, int) - Method in class lejos.remote.nxt.RemoteNXTAudio
 
playSoundFile(String, boolean) - Method in class lejos.remote.nxt.NXTCommand
 
playTone(int, int, int) - Method in interface lejos.hardware.Audio
Plays a tone, given its frequency and duration.
playTone(int, int) - Method in interface lejos.hardware.Audio
 
playTone(int, int, int) - Static method in class lejos.hardware.Sound
Plays a tone, given its frequency and duration.
playTone(int, int) - Static method in class lejos.hardware.Sound
Plays a tone, given its frequency and duration.
playTone(int, int, int) - Method in class lejos.remote.ev3.RemoteAudio
 
playTone(int, int) - Method in class lejos.remote.ev3.RemoteAudio
 
playTone(int, int, int) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
playTone(int, int) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
playTone(int, int, int) - Method in interface lejos.remote.ev3.RMIAudio
Plays a tone, given its frequency and duration.
playTone(int, int) - Method in interface lejos.remote.ev3.RMIAudio
 
playTone(int, int, int) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
playTone(int, int) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
playTone(int, int) - Method in class lejos.remote.nxt.NXTCommand
Plays a tone on NXT speaker.
playTone(int, int, int) - Method in class lejos.remote.nxt.RemoteNXTAudio
 
playTone(int, int) - Method in class lejos.remote.nxt.RemoteNXTAudio
 
plus(Matrix) - Method in class lejos.utility.Matrix
C = A + B
plusEquals(Matrix) - Method in class lejos.utility.Matrix
A = A + B
Point - Class in lejos.robotics.geometry
Point with float co-ordinates for use in navigation.
Point(float, float) - Constructor for class lejos.robotics.geometry.Point
returns a Point at location x,y
Point(float) - Constructor for class lejos.robotics.geometry.Point
Returns a point ad distance 1 from the origin and an angle radans to the x-axis
Point2D - Class in lejos.robotics.geometry
An abstract class for a point.
Point2D() - Constructor for class lejos.robotics.geometry.Point2D
This is abstract class that cannot be instantiated.
Point2D.Double - Class in lejos.robotics.geometry
A point with double coordinates.
Point2D.Float - Class in lejos.robotics.geometry
A point with float coordinates.
pointAt(float, float) - Method in class lejos.robotics.geometry.Point
Returns a new point at the specified distance in the direction angle from this point.
pointAt(float, float) - Method in class lejos.robotics.navigation.Pose
Returns the point at distance from the location of this pose, in the direction bearing relative to the X axis.
polarPosition(double, double) - Method in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
Specifies the location and orientation of the wheel using polar coordinates
POLL - Static variable in class lejos.remote.nxt.LCP
 
POLL - Static variable in interface lejos.remote.nxt.NXTProtocol
 
POLL_BUFFER - Static variable in interface lejos.remote.nxt.NXTProtocol
 
POLL_LENGTH - Static variable in class lejos.remote.nxt.LCP
 
POLL_LENGTH - Static variable in interface lejos.remote.nxt.NXTProtocol
 
port - Variable in class lejos.hardware.device.DeviceIdentifier
 
port - Variable in class lejos.hardware.device.UART
 
port - Variable in class lejos.hardware.motor.BasicMotor
 
Port - Interface in lejos.hardware.port
Interface that provides a binding between a physical port and the different types of sensor interfaces that can be used with it
port - Variable in class lejos.hardware.sensor.AnalogSensor
 
port - Variable in class lejos.hardware.sensor.I2CSensor
 
port - Variable in class lejos.hardware.sensor.UARTSensor
 
port - Variable in class lejos.remote.ev3.RemoteIOPort
 
port - Variable in class lejos.remote.ev3.RemoteRequestIOPort
 
port - Variable in class lejos.remote.nxt.RemoteNXTIOPort
 
port - Variable in class lejos.robotics.filter.PublishedSource
 
PortException - Exception in lejos.hardware.port
Exception thrown when errors are detected accessing a port.
PortException() - Constructor for exception lejos.hardware.port.PortException
 
PortException(String) - Constructor for exception lejos.hardware.port.PortException
 
PortException(Throwable) - Constructor for exception lejos.hardware.port.PortException
 
PortException(String, Throwable) - Constructor for exception lejos.hardware.port.PortException
 
portNum - Variable in class lejos.remote.ev3.RemotePort
 
portNum - Variable in class lejos.remote.ev3.RemoteRequestPort
 
portNum - Variable in class lejos.remote.nxt.RemoteNXTPort
 
ports - Variable in class lejos.hardware.ev3.LocalEV3
 
PORTS - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
ports - Variable in class lejos.remote.nxt.RemoteNXT
 
pose - Variable in class lejos.robotics.chassis.WheeledChassis.HolonomicModeler
 
Pose - Class in lejos.robotics.navigation
Represents the location and heading(direction angle) of a robot.
This class includes methods for updating the Pose to in response to basic robot movements.
Pose() - Constructor for class lejos.robotics.navigation.Pose
allocate a new Pose at the origin, heading = 0:the direction the positive X axis
Pose(float, float, float) - Constructor for class lejos.robotics.navigation.Pose
Allocate a new pose at location (x,y) with specified heading in degrees.
PoseProvider - Interface in lejos.robotics.localization
Provides the coordinate and heading info via a Pose object.
postCommand(byte[], int, byte[], int) - Method in class lejos.remote.nxt.LCPResponder
 
power - Variable in class lejos.hardware.motor.BasicMotor
 
power - Variable in class lejos.hardware.motor.JavaMotorRegulator
 
Power - Interface in lejos.hardware
Interface used to access information about the EV3 battery and current usage.
POWER_OFF_RCX - Static variable in class lejos.hardware.device.RCXLink
 
powerOff() - Method in class lejos.hardware.device.RCXLink
 
powerOff() - Method in class lejos.hardware.sensor.MindsensorsDistanceSensorV2
Turns power to the sensor module off.
powerOn() - Method in class lejos.hardware.sensor.MindsensorsDistanceSensorV2
Turns the sensor module on.
powerSetpoint - Variable in class lejos.remote.nxt.OutputState
 
powerUp(boolean) - Method in class lejos.hardware.device.PSPNXController
 
pp - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
preCommand(byte[], int) - Method in class lejos.remote.nxt.LCPResponder
Method called with a newly read command, before it is processed.
PressureDetector - Interface in lejos.robotics
Interface for pressure sensors.
print(PrintStream) - Method in class lejos.utility.Matrix
 
printReadings() - Method in class lejos.robotics.RangeReadings
Print the range readings on standard out
processData() - Method in class lejos.hardware.sensor.MindsensorsBTSense
Process data from the phone application
projectOn(Line) - Method in class lejos.robotics.geometry.Point
Finds the orthogonal projection of this point onto the line.
protocolVersion - Variable in class lejos.remote.nxt.FirmwareInfo
 
PSPNXController - Class in lejos.hardware.device
This class allows you to use a Sony Playstation 2 controller to control your robot in conjunction with the Mindsensors.com PSP-Nx interface.
PSPNXController(I2CPort) - Constructor for class lejos.hardware.device.PSPNXController
 
PSPNXController(I2CPort, int) - Constructor for class lejos.hardware.device.PSPNXController
 
PSPNXController(Port) - Constructor for class lejos.hardware.device.PSPNXController
 
PSPNXController(Port, int) - Constructor for class lejos.hardware.device.PSPNXController
 
ptSegDist(double, double, double, double, double, double) - Static method in class lejos.robotics.geometry.Line2D
Measures the shortest distance from the reference point to a point on the line segment.
ptSegDist(double, double) - Method in class lejos.robotics.geometry.Line2D
Measures the shortest distance from the reference point to a point on this line segment.
ptSegDist(Point2D) - Method in class lejos.robotics.geometry.Line2D
Measures the shortest distance from the reference point to a point on this line segment.
ptSegDistSq(double, double, double, double, double, double) - Static method in class lejos.robotics.geometry.Line2D
Measures the square of the shortest distance from the reference point to a point on the line segment.
ptSegDistSq(double, double) - Method in class lejos.robotics.geometry.Line2D
Measures the square of the shortest distance from the reference point to a point on this line segment.
ptSegDistSq(Point2D) - Method in class lejos.robotics.geometry.Line2D
Measures the square of the shortest distance from the reference point to a point on this line segment.
PUBLISH_PORT - Static variable in class lejos.robotics.filter.PublishedSource
 
PUBLISH_PORT - Static variable in class lejos.robotics.filter.PublishFilter
 
PublishedSource - Class in lejos.robotics.filter
 
PublishedSource(String, byte[]) - Constructor for class lejos.robotics.filter.PublishedSource
 
publisher - Variable in class lejos.robotics.filter.PublishFilter
 
PublishFilter - Class in lejos.robotics.filter
 
PublishFilter(SampleProvider, String, float) - Constructor for class lejos.robotics.filter.PublishFilter
 
publishMessage - Variable in class lejos.robotics.filter.PublishFilter
 
publishPacket - Variable in class lejos.robotics.filter.PublishFilter
 
PWM_BRAKE - Static variable in interface lejos.hardware.port.BasicMotorPort
PWM Mode.
PWM_FLOAT - Static variable in interface lejos.hardware.port.BasicMotorPort
PWM Mode.

Q

quickStop() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Stops the robot almost immediately.
quit() - Method in class lejos.utility.TextMenu
method to call from another thread to quit the menu

R

random(int, int) - Static method in class lejos.utility.Matrix
Generate matrix with random elements
RandomPathFinder - Class in lejos.robotics.pathfinding
PathFinder that takes a map and a dummy set of range readings.
RandomPathFinder(RangeMap, RangeReadings) - Constructor for class lejos.robotics.pathfinding.RandomPathFinder
 
RandomSelfGeneratingNode - Class in lejos.robotics.pathfinding
This Node is able to randomly generate its own neighbors via the getNeighbors() method.
RandomSelfGeneratingNode(float, float, float, int) - Constructor for class lejos.robotics.pathfinding.RandomSelfGeneratingNode
Creates a node that will randomly generate 'connections' number of neighbors when getNeighbors() is called.
RandomSelfGeneratingNode(float, float, float, int, Node) - Constructor for class lejos.robotics.pathfinding.RandomSelfGeneratingNode
Creates a node that will randomly generate 'connections' number of neighbors when getNeighbors() is called.
range(Pose) - Method in class lejos.robotics.mapping.LineMap
Calculate the range of a robot to the nearest wall
range(Pose) - Method in interface lejos.robotics.mapping.RangeMap
The the range to the nearest wall (or other feature)
RangeFeature - Class in lejos.robotics.objectdetection
This class is a basic data container for information retrieved about an object detected by sensors.
RangeFeature(RangeReading) - Constructor for class lejos.robotics.objectdetection.RangeFeature
Creates a RangeFeature containing a single RangeReading.
RangeFeature(RangeReadings) - Constructor for class lejos.robotics.objectdetection.RangeFeature
Creates a RangeFeature containing multiple RangeReadings.
RangeFeature(RangeReadings, Pose) - Constructor for class lejos.robotics.objectdetection.RangeFeature
Creates a RangeFeature containing multiple RangeReadings.
RangeFeatureDetector - Class in lejos.robotics.objectdetection
The RangeFeatureDetector used a RangeFinder to locate objects (known as features when mapping).
RangeFeatureDetector(RangeFinder, float, int) - Constructor for class lejos.robotics.objectdetection.RangeFeatureDetector
This constructor allows you to specify the sensor, the maximum distance to report a detection, and the delay between scanning the sensor.
RangeFeatureDetector(RangeFinder, float, int, double) - Constructor for class lejos.robotics.objectdetection.RangeFeatureDetector
This constructor allows you to specify the sensor, the maximum distance to report a detection, the delay between scanning the sensor, and the angle the sensor is pointed.
rangeFinder - Variable in class lejos.robotics.FixedRangeScanner
 
RangeFinder - Interface in lejos.robotics
Abstraction for a range finder sensor that returns the distance to the nearest object
rangeFinder - Variable in class lejos.robotics.RotatingRangeScanner
 
RangeFinderAdapter - Class in lejos.robotics
 
RangeFinderAdapter(SampleProvider) - Constructor for class lejos.robotics.RangeFinderAdapter
 
RangeMap - Interface in lejos.robotics.mapping
The RangeMap interface supports determining the range to a feature on the map (such as a wall), from an object with a specific pose.
RangeReading - Class in lejos.robotics
Represent a single range reading
RangeReading(float, float) - Constructor for class lejos.robotics.RangeReading
Create the reading
RangeReadings - Class in lejos.robotics
Represents a set of range readings.
RangeReadings(int) - Constructor for class lejos.robotics.RangeReadings
 
RangeScanner - Interface in lejos.robotics
Abstraction for a single range scanning sensor, rotating platform with a range finder, or a complete robot, that obtains a set of range readings at a set of angles to# the robot's heading.
raw - Variable in class lejos.hardware.sensor.EV3ColorSensor
 
RAW - Static variable in class lejos.remote.nxt.NXTConnection
RAW I/O mode.
rawADValue - Variable in class lejos.remote.nxt.InputValues
The raw value from the Analog to Digital (AD) converter.
RAWMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
rawRead(byte[], int, int) - Method in interface lejos.hardware.port.UARTPort
Read bytes from the uart port.
rawRead(byte[], int, int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
rawRead(byte[], int, int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
rawRead(byte[], int, int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
rawRead(byte[], int, int) - Method in interface lejos.remote.ev3.RMIUARTPort
Read bytes from the uart port.
rawWrite(byte[], int, int) - Method in interface lejos.hardware.port.UARTPort
Attempt to write a series of bytes to the uart port.
rawWrite(byte[], int, int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
rawWrite(byte[], int, int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
rawWrite(byte[], int, int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
rawWrite(byte[], int, int) - Method in interface lejos.remote.ev3.RMIUARTPort
Attempt to write a series of bytes to the uart port.
RCX_REMOTE_A_BWD - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_A_FWD - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_B_BWD - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_B_FWD - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_BEEP - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_C_BWD - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_C_FWD - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_MSG1 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_MSG2 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_MSG3 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_P1 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_P2 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_P3 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_P4 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_P5 - Static variable in class lejos.hardware.device.IRLink
 
RCX_REMOTE_STOP - Static variable in class lejos.hardware.device.IRLink
 
RCXAbstractPort - Class in lejos.remote.rcx
RCXAbstractPort provides an interface similar to java.net.Socket Adapted from original code created by the LEGO3 Team at DTU-IAU RCXAbstractPort implements input and output stream handling and input buffering.
RCXAbstractPort(PacketHandler) - Constructor for class lejos.remote.rcx.RCXAbstractPort
Constructor for the RCXAbstractPort.
RCXLightSensor - Class in lejos.hardware.sensor
LEGO RCX light Sensor
The RCX light sensor measures light levels of reflected or ambient light.
RCXLightSensor(Port) - Constructor for class lejos.hardware.sensor.RCXLightSensor
Create an RCX light sensor object attached to the specified port.
RCXLink - Class in lejos.hardware.device
Supports Mindsensors NRLink RCX IR adapter.
RCXLink(I2CPort) - Constructor for class lejos.hardware.device.RCXLink
 
RCXLink(Port) - Constructor for class lejos.hardware.device.RCXLink
 
RCXMotor - Class in lejos.hardware.motor
Abstraction for an RCX motor.
RCXMotor(BasicMotorPort) - Constructor for class lejos.hardware.motor.RCXMotor
 
RCXMotor(Port) - Constructor for class lejos.hardware.motor.RCXMotor
 
RCXMotorMultiplexer - Class in lejos.hardware.device
Supports the mindsensors RCX Motor Multiplexer
RCXMotorMultiplexer(I2CPort) - Constructor for class lejos.hardware.device.RCXMotorMultiplexer
 
RCXMotorMultiplexer(I2CPort, int) - Constructor for class lejos.hardware.device.RCXMotorMultiplexer
 
RCXMotorMultiplexer(Port) - Constructor for class lejos.hardware.device.RCXMotorMultiplexer
 
RCXMotorMultiplexer(Port, int) - Constructor for class lejos.hardware.device.RCXMotorMultiplexer
 
RCXPlexedMotorPort - Class in lejos.hardware.device
Supports a motor connected to the Mindsensors RCX Motor Multiplexer
RCXPlexedMotorPort(RCXMotorMultiplexer, int) - Constructor for class lejos.hardware.device.RCXPlexedMotorPort
 
RCXPort - Class in lejos.remote.rcx
RCXPort provides an interface similar to java.net.Socket Adapted from original code created by the LEGO3 Team at DTU-IAU Uses Reliable low-level comms for communication.
RCXPort(I2CPort) - Constructor for class lejos.remote.rcx.RCXPort
 
RCXRemoteMotorPort - Class in lejos.remote.rcx
Supports a motor connected to a remote RCX via a mindsensord NRLink adapter
RCXRemoteMotorPort(RCXLink, int) - Constructor for class lejos.remote.rcx.RCXRemoteMotorPort
 
RCXRotationSensor - Class in lejos.hardware.sensor
Provide access to the Lego RCX Rotation Sensor.
RCXRotationSensor(Port) - Constructor for class lejos.hardware.sensor.RCXRotationSensor
Create an RCX rotation sensor object attached to the specified port.
RCXRotationSensor.Reader - Class in lejos.hardware.sensor
 
RCXSensorMultiplexer - Class in lejos.hardware.device
Supports Mindsensors RXMux
This sensor allows you to connect up to four RCX type sensors toa single port.
RCXSensorMultiplexer(I2CPort) - Constructor for class lejos.hardware.device.RCXSensorMultiplexer
 
RCXSensorMultiplexer(I2CPort, int) - Constructor for class lejos.hardware.device.RCXSensorMultiplexer
 
RCXSensorMultiplexer(Port) - Constructor for class lejos.hardware.device.RCXSensorMultiplexer
 
RCXSensorMultiplexer(Port, int) - Constructor for class lejos.hardware.device.RCXSensorMultiplexer
 
RCXThermometer - Class in lejos.hardware.sensor
Lego RCX temperature sensor
The sensor measures both atmospheric pressure and temperature.
RCXThermometer(LegacySensorPort) - Constructor for class lejos.hardware.sensor.RCXThermometer
Create an RCX temperature sensor object attached to the specified port.
read(byte[], int, int) - Method in class lejos.hardware.device.UART
Read bytes from the device.
read() - Method in class lejos.hardware.device.UART.UARTInputStream
 
read(byte[], int, int) - Method in class lejos.hardware.device.UART.UARTInputStream
 
read(byte[], int) - Method in class lejos.remote.nxt.BTConnection
 
read(byte[], int, boolean) - Method in class lejos.remote.nxt.BTConnection
 
READ - Static variable in class lejos.remote.nxt.LCP
 
read(byte[], int) - Method in class lejos.remote.nxt.NXTConnection
 
read(byte[], int, boolean) - Method in class lejos.remote.nxt.NXTConnection
 
read(byte[], int, int) - Method in class lejos.remote.nxt.NXTInputStream
 
read() - Method in class lejos.remote.nxt.NXTInputStream
Returns one byte as an integer between 0 and 255.
READ - Static variable in interface lejos.remote.nxt.NXTProtocol
 
read(byte[], int) - Method in class lejos.remote.nxt.SocketConnection
 
read(byte[], int, boolean) - Method in class lejos.remote.nxt.SocketConnection
 
read() - Static method in class lejos.remote.rcx.LLC
read a single byte, if available
readButtons() - Static method in class lejos.hardware.Button
Low-level API that reads status of buttons.
readButtons() - Method in class lejos.hardware.device.MindSensorsNumPad
Returns a Bitmask.
readButtons() - Method in interface lejos.hardware.Keys
 
readButtons() - Method in class lejos.remote.ev3.RemoteKeys
 
readButtons() - Method in class lejos.remote.ev3.RemoteRequestKeys
 
readButtons() - Method in interface lejos.remote.ev3.RMIKeys
 
readButtons() - Method in class lejos.remote.ev3.RMIRemoteKeys
 
readBytes(byte[]) - Method in class lejos.hardware.device.RCXLink
 
reader - Variable in class lejos.hardware.sensor.RCXRotationSensor
 
Reader() - Constructor for class lejos.hardware.sensor.RCXRotationSensor.Reader
 
readFile(byte, byte[], int, int) - Method in class lejos.remote.nxt.NXTCommand
Returns requested number of bytes from a file.
readFull() - Method in class lejos.hardware.sensor.NXTColorSensor
 
readings - Variable in class lejos.robotics.FixedRangeScanner
 
readings - Variable in class lejos.robotics.mapping.NavigationModel
 
readings - Variable in class lejos.robotics.RotatingRangeScanner
 
readLineMap() - Method in class lejos.robotics.mapping.ShapefileLoader
Retrieves a LineMap object from the Shapefile input stream.
readLineMap() - Method in class lejos.robotics.mapping.SVGMapLoader
 
readPacket(byte[]) - Static method in class lejos.remote.rcx.Serial
Read an assembled packet.
readRaw() - Method in class lejos.hardware.sensor.NXTColorSensor
 
readSensors() - Method in class lejos.hardware.device.TouchMUX
Read the touch multiplexer and return a bit mask showing which sensors are currently pressed.
readTransponder(boolean) - Method in class lejos.hardware.sensor.RFIDSensor
Read a transponder id.
readTransponderAsLong(boolean) - Method in class lejos.hardware.sensor.RFIDSensor
 
readValue(int) - Method in class lejos.hardware.device.SensorMux
Method used to receive data from a Sound Sensor
recalibrateOffset() - Method in interface lejos.robotics.Gyroscope
Implementor must calculate and set the offset/bias value for use in getAngularVelocity().
recalibrateOffset() - Method in class lejos.robotics.GyroscopeAdapter
Racalibrates the gyroscope for offset error.
receive() - Static method in class lejos.remote.rcx.LLC
wait a little while for a byte to become available
receiveAck(byte[]) - Method in class lejos.remote.rcx.LLCHandler
Receive an ack.
receiveAck(byte[]) - Method in class lejos.remote.rcx.PacketHandler
 
receivePacket(byte[]) - Method in class lejos.remote.rcx.LLCHandler
Receive a packet.
receivePacket(byte[]) - Method in class lejos.remote.rcx.LLCReliableHandler
Receive a packet.
receivePacket(byte[]) - Method in class lejos.remote.rcx.PacketHandler
Receive a packet.
Rectangle - Class in lejos.robotics.geometry
 
Rectangle(float, float, float, float) - Constructor for class lejos.robotics.geometry.Rectangle
 
Rectangle2D - Class in lejos.robotics.geometry
An abstract class for a Rectangle.
Rectangle2D() - Constructor for class lejos.robotics.geometry.Rectangle2D
This is an abstract class which cannot be instantiated: use Rectangle2D.Float, Rectangle2D.Double, or Rectangle.
Rectangle2D.Double - Class in lejos.robotics.geometry
A Rectangle2D with double coordinates
Rectangle2D.Float - Class in lejos.robotics.geometry
A Rectangle2D with float coordinates.
RectangleInt32 - Class in lejos.robotics.geometry
A rectangle with integer coordinates.
RectangleInt32(int, int, int, int) - Constructor for class lejos.robotics.geometry.RectangleInt32
Creates a rectangle with top left corner at (x,y) and with specified width and height.
RectangleInt32(int, int) - Constructor for class lejos.robotics.geometry.RectangleInt32
Creates a rectangle with top left corner at (0,0) and with specified width and height.
RectangleInt32() - Constructor for class lejos.robotics.geometry.RectangleInt32
Creates an empty rectangle at (0,0).
RectangleInt32(Point) - Constructor for class lejos.robotics.geometry.RectangleInt32
Create an empty rectangle at the given point
RectangularShape - Class in lejos.robotics.geometry
An abstract base class for shapes based on a rectangular frame.
RectangularShape() - Constructor for class lejos.robotics.geometry.RectangularShape
 
RED - Static variable in interface lejos.hardware.sensor.SensorConstants
 
RED - Static variable in class lejos.robotics.Color
 
RED_INDEX - Static variable in interface lejos.hardware.sensor.SensorConstants
Color sensor data RED value index.
ref - Variable in class lejos.remote.ev3.RemoteIOPort
 
ref - Variable in class lejos.remote.ev3.RemoteRequestIOPort
 
ref - Variable in class lejos.remote.nxt.RemoteNXTIOPort
 
REFLECTION - Static variable in interface lejos.remote.nxt.NXTProtocol
 
refresh() - Method in interface lejos.hardware.lcd.CommonLCD
Refresh the display.
refresh() - Static method in class lejos.hardware.lcd.LCD
Refresh the display.
refresh() - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
refresh() - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
refresh() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
refresh() - Method in class lejos.remote.ev3.RemoteTextLCD
 
refresh() - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
refresh() - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
refresh() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
refresh() - Method in interface lejos.remote.ev3.RMITextLCD
 
reg - Variable in class lejos.hardware.motor.BaseRegulatedMotor
 
REG_ACCUMULATED_ANGLE - Static variable in class lejos.hardware.sensor.HiTechnicAngleSensor
 
REG_ANGLE - Static variable in class lejos.hardware.sensor.HiTechnicAngleSensor
 
REG_CONFIG - Static variable in class lejos.hardware.sensor.DexterCompassSensor
 
REG_MAGNETO - Static variable in class lejos.hardware.sensor.DexterCompassSensor
 
REG_PRODUCT_ID - Static variable in class lejos.hardware.sensor.I2CSensor
Register number of sensor product ID, as defined by standard Lego I2C register layout.
REG_SPEED - Static variable in class lejos.hardware.sensor.HiTechnicAngleSensor
 
REG_STATUS - Static variable in class lejos.hardware.sensor.DexterCompassSensor
 
REG_VENDOR_ID - Static variable in class lejos.hardware.sensor.I2CSensor
Register number of sensor vendor ID, as defined by standard Lego I2C register layout.
REG_VERSION - Static variable in class lejos.hardware.sensor.I2CSensor
Register number of sensor version string, as defined by standard Lego I2C register layout.
regenerate() - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
regenerate() - Method in interface lejos.robotics.pathfinding.NavigationMesh
Throws away the previous set of nodes and recalculates them all.
REGULATED - Static variable in interface lejos.remote.nxt.NXTProtocol
Turns on the regulation
RegulatedMotor - Interface in lejos.robotics
Interface for encoded motors without limited range of movement (e.g.
RegulatedMotorListener - Interface in lejos.robotics
This interface defines a listener that is notified of the tachometer when the motor starts and stops rotating.
REGULATION_MODE_IDLE - Static variable in interface lejos.remote.nxt.NXTProtocol
No regulation will be enabled
REGULATION_MODE_MOTOR_SPEED - Static variable in interface lejos.remote.nxt.NXTProtocol
Power control will be enabled on specified output
REGULATION_MODE_MOTOR_SYNC - Static variable in interface lejos.remote.nxt.NXTProtocol
Synchronization will be enabled (Needs enabled on two output)
regulationMode - Variable in class lejos.remote.nxt.OutputState
 
regulator - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
relativeBearing(Point) - Method in class lejos.robotics.navigation.Pose
Returns the angle to destination relative to the pose heading;
relativeCCW(double, double, double, double, double, double) - Static method in class lejos.robotics.geometry.Line2D
Returns an indicator of where the specified point lies with respect to the line
relativeCCW(Point2D) - Method in class lejos.robotics.geometry.Line2D
Returns an indicator of where the specified point lies with respect to the line
relativeCCW(double, double) - Method in class lejos.robotics.geometry.Line2D
Returns an indicator of where the specified point lies with respect to the line.
releaseOnClose(Closeable) - Method in class lejos.hardware.Device
Add the specified resource to the list of objects that will be closed when the sensor is closed.
RemoteAnalogPort - Class in lejos.remote.ev3
 
RemoteAnalogPort(RMIEV3) - Constructor for class lejos.remote.ev3.RemoteAnalogPort
 
RemoteAudio - Class in lejos.remote.ev3
 
RemoteAudio(RMIAudio) - Constructor for class lejos.remote.ev3.RemoteAudio
 
RemoteBattery - Class in lejos.remote.ev3
 
RemoteBattery(RMIBattery) - Constructor for class lejos.remote.ev3.RemoteBattery
 
RemoteBTDevice - Class in lejos.hardware
 
RemoteBTDevice(String, byte[], int) - Constructor for class lejos.hardware.RemoteBTDevice
 
RemoteEV3 - Class in lejos.remote.ev3
 
RemoteEV3(String) - Constructor for class lejos.remote.ev3.RemoteEV3
 
RemoteGraphicsLCD - Class in lejos.remote.ev3
 
RemoteGraphicsLCD(RMIGraphicsLCD) - Constructor for class lejos.remote.ev3.RemoteGraphicsLCD
 
RemoteI2CPort - Class in lejos.remote.ev3
 
RemoteI2CPort(RMIEV3) - Constructor for class lejos.remote.ev3.RemoteI2CPort
 
RemoteIOPort - Class in lejos.remote.ev3
 
RemoteIOPort() - Constructor for class lejos.remote.ev3.RemoteIOPort
 
RemoteKey - Class in lejos.remote.ev3
 
RemoteKey(RMIKey, RemoteKeys, String) - Constructor for class lejos.remote.ev3.RemoteKey
 
RemoteKeys - Class in lejos.remote.ev3
 
RemoteKeys(RMIKeys) - Constructor for class lejos.remote.ev3.RemoteKeys
 
RemoteLED - Class in lejos.remote.ev3
 
RemoteLED(RMILED) - Constructor for class lejos.remote.ev3.RemoteLED
 
RemoteMotorPort - Class in lejos.remote.ev3
 
RemoteMotorPort(RMIEV3) - Constructor for class lejos.remote.ev3.RemoteMotorPort
 
RemoteNXT - Class in lejos.remote.nxt
 
RemoteNXT(String, NXTCommConnector) - Constructor for class lejos.remote.nxt.RemoteNXT
 
RemoteNXT(String, byte[]) - Constructor for class lejos.remote.nxt.RemoteNXT
 
RemoteNXTAnalogPort - Class in lejos.remote.nxt
This class provides access to the EV3 Analog based sensor ports and other analog data sources.
RemoteNXTAnalogPort(NXTCommand) - Constructor for class lejos.remote.nxt.RemoteNXTAnalogPort
 
RemoteNXTAudio - Class in lejos.remote.nxt
 
RemoteNXTAudio(NXTCommand) - Constructor for class lejos.remote.nxt.RemoteNXTAudio
 
RemoteNXTBattery - Class in lejos.remote.nxt
Battery readings from a remote NXT.
RemoteNXTBattery(NXTCommand) - Constructor for class lejos.remote.nxt.RemoteNXTBattery
 
RemoteNXTI2CPort - Class in lejos.remote.nxt
 
RemoteNXTI2CPort(NXTCommand) - Constructor for class lejos.remote.nxt.RemoteNXTI2CPort
 
RemoteNXTIOPort - Class in lejos.remote.nxt
This class provides the base operations for remote NXT sensor ports.
RemoteNXTIOPort(NXTCommand) - Constructor for class lejos.remote.nxt.RemoteNXTIOPort
 
RemoteNXTMotorPort - Class in lejos.remote.nxt
Abstraction for an EV3 output port.
RemoteNXTMotorPort(NXTCommand) - Constructor for class lejos.remote.nxt.RemoteNXTMotorPort
 
RemoteNXTPort - Class in lejos.remote.nxt
 
RemoteNXTPort(String, int, int, NXTCommand) - Constructor for class lejos.remote.nxt.RemoteNXTPort
 
RemotePort - Class in lejos.remote.ev3
 
RemotePort(String, int, int, RMIEV3) - Constructor for class lejos.remote.ev3.RemotePort
 
RemoteRequestAnalogPort - Class in lejos.remote.ev3
 
RemoteRequestAnalogPort(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestAnalogPort
 
RemoteRequestAudio - Class in lejos.remote.ev3
 
RemoteRequestAudio(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestAudio
 
RemoteRequestBattery - Class in lejos.remote.ev3
 
RemoteRequestBattery(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestBattery
 
RemoteRequestEV3 - Class in lejos.remote.ev3
 
RemoteRequestEV3(String) - Constructor for class lejos.remote.ev3.RemoteRequestEV3
 
RemoteRequestException - Exception in lejos.remote.ev3
Exception thrown when errors are detected in a sensor device state.
RemoteRequestException() - Constructor for exception lejos.remote.ev3.RemoteRequestException
 
RemoteRequestException(String) - Constructor for exception lejos.remote.ev3.RemoteRequestException
 
RemoteRequestException(Throwable) - Constructor for exception lejos.remote.ev3.RemoteRequestException
 
RemoteRequestException(String, Throwable) - Constructor for exception lejos.remote.ev3.RemoteRequestException
 
RemoteRequestGraphicsLCD - Class in lejos.remote.ev3
 
RemoteRequestGraphicsLCD(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
RemoteRequestI2CPort - Class in lejos.remote.ev3
 
RemoteRequestI2CPort(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestI2CPort
 
RemoteRequestIOPort - Class in lejos.remote.ev3
 
RemoteRequestIOPort() - Constructor for class lejos.remote.ev3.RemoteRequestIOPort
 
RemoteRequestKey - Class in lejos.remote.ev3
 
RemoteRequestKey(ObjectInputStream, ObjectOutputStream, RemoteRequestKeys, String) - Constructor for class lejos.remote.ev3.RemoteRequestKey
 
RemoteRequestKeys - Class in lejos.remote.ev3
 
RemoteRequestKeys(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestKeys
 
RemoteRequestLED - Class in lejos.remote.ev3
 
RemoteRequestLED(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestLED
 
RemoteRequestMenu - Class in lejos.remote.ev3
 
RemoteRequestMenu(String) - Constructor for class lejos.remote.ev3.RemoteRequestMenu
 
RemoteRequestMotorPort - Class in lejos.remote.ev3
 
RemoteRequestMotorPort(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestMotorPort
 
RemoteRequestPilot - Class in lejos.remote.ev3
 
RemoteRequestPilot(ObjectInputStream, ObjectOutputStream, String, String, double, double) - Constructor for class lejos.remote.ev3.RemoteRequestPilot
 
RemoteRequestPort - Class in lejos.remote.ev3
 
RemoteRequestPort(String, int, int, ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestPort
 
RemoteRequestRegulatedMotor - Class in lejos.remote.ev3
 
RemoteRequestRegulatedMotor(ObjectInputStream, ObjectOutputStream, String, char) - Constructor for class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
RemoteRequestSampleProvider - Class in lejos.remote.ev3
 
RemoteRequestSampleProvider(ObjectInputStream, ObjectOutputStream, String, String, String) - Constructor for class lejos.remote.ev3.RemoteRequestSampleProvider
 
RemoteRequestSampleProvider(ObjectInputStream, ObjectOutputStream, String, String, String, String, float) - Constructor for class lejos.remote.ev3.RemoteRequestSampleProvider
 
RemoteRequestTextLCD - Class in lejos.remote.ev3
 
RemoteRequestTextLCD(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestTextLCD
 
RemoteRequestTextLCD(ObjectInputStream, ObjectOutputStream, Font) - Constructor for class lejos.remote.ev3.RemoteRequestTextLCD
 
RemoteRequestUARTPort - Class in lejos.remote.ev3
 
RemoteRequestUARTPort(ObjectInputStream, ObjectOutputStream) - Constructor for class lejos.remote.ev3.RemoteRequestUARTPort
 
RemoteTextLCD - Class in lejos.remote.ev3
 
RemoteTextLCD(RMITextLCD) - Constructor for class lejos.remote.ev3.RemoteTextLCD
 
RemoteUARTPort - Class in lejos.remote.ev3
 
RemoteUARTPort(RMIEV3) - Constructor for class lejos.remote.ev3.RemoteUARTPort
 
remoteVals - Variable in class lejos.hardware.sensor.EV3IRSensor
 
removeDevice(String) - Method in class lejos.hardware.LocalBTDevice
Remove the specified device from the known/paired list
removeListener() - Method in class lejos.hardware.device.MMXRegulatedMotor
 
removeListener() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
removeListener(GPSListener) - Static method in class lejos.hardware.gps.SimpleGPS
Remove a listener
removeListener() - Method in class lejos.hardware.motor.BaseRegulatedMotor
 
removeListener() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
removeListener() - Method in interface lejos.hardware.motor.MotorRegulator
 
removeListener() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
removeListener() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Removes the RegulatedMotorListener from this class.
removeListener() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
removeListener() - Method in class lejos.robotics.MirrorMotor
 
removeListener() - Method in interface lejos.robotics.RegulatedMotor
Removes the RegulatedMotorListener from this class.
removeNeighbor(Node) - Method in class lejos.robotics.pathfinding.Node
Removes a node from this node as neighbors, effectively disconnecting them.
removeNode(Node) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
removeNode(Node) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Removes a node from the set and removes any existing connections with its neighbors.
reply - Variable in class lejos.remote.ev3.EV3Reply
 
reply - Variable in class lejos.remote.ev3.MenuReply
 
REPLY_COMMAND - Static variable in class lejos.remote.nxt.LCP
 
REPLY_COMMAND - Static variable in interface lejos.remote.nxt.NXTProtocol
 
replyRequired - Variable in class lejos.remote.ev3.EV3Request
 
replyRequired - Variable in class lejos.remote.ev3.MenuRequest
 
request - Variable in class lejos.remote.ev3.EV3Request
 
request - Variable in class lejos.remote.ev3.MenuRequest
 
REQUEST_FAILED - Static variable in class lejos.remote.nxt.ErrorMessages
Request failed (i.e.
resample() - Method in class lejos.robotics.localization.MCLParticleSet
Resample the set picking those with higher weights.
reset() - Method in class lejos.hardware.motor.JavaMotorRegulator
Reset the tachometer readings
reset() - Method in class lejos.hardware.sensor.CruizcoreGyro
Resets the accumulated angle (heading).
reset() - Method in class lejos.hardware.sensor.EV3GyroSensor
Hardware calibration of the Gyro sensor and reset off accumulated angle to zero.
reset() - Method in class lejos.remote.nxt.RemoteNXTI2CPort
 
reset() - Method in class lejos.remote.rcx.LLCReliableHandler
Reset sequence numbers.
reset() - Method in class lejos.remote.rcx.PacketHandler
Reset sequence numbers for this handler
reset() - Method in class lejos.remote.rcx.RCXAbstractPort
Resets sequence numbers for this port
reset() - Method in class lejos.robotics.filter.OffsetCorrectionFilter
Resets the filter
reset() - Method in interface lejos.robotics.Gyroscope
 
reset() - Method in class lejos.robotics.GyroscopeAdapter
 
reset() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
reset() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Resets tacho count for both motors.
reset() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Reset all tacho counts.
reset() - Method in class lejos.utility.Stopwatch
Reset watch to zero
RESET_MOTOR_POSITION - Static variable in class lejos.remote.nxt.LCP
 
RESET_MOTOR_POSITION - Static variable in interface lejos.remote.nxt.NXTProtocol
 
RESET_SCALED_INPUT_VALUE - Static variable in class lejos.remote.nxt.LCP
 
RESET_SCALED_INPUT_VALUE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
resetAccumulatedAngle() - Method in class lejos.hardware.sensor.HiTechnicAngleSensor
Reset the rotation count of accumulated angle to zero.
resetCartesianZero() - Method in interface lejos.robotics.DirectionFinder
Changes the current direction the compass is facing into the zero angle.
resetCartesianZero() - Method in class lejos.robotics.DirectionFinderAdapter
 
resetCartesianZero() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
resetCartesianZero() - Method in class lejos.utility.GyroDirectionFinder
Resets the current heading to zero.
resetMotorPosition(int, boolean) - Method in class lejos.remote.nxt.NXTCommand
Resets either RotationCount or BlockTacho
resetSensor() - Method in interface lejos.hardware.port.UARTPort
Reset the attached sensor.
resetSensor() - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
resetSensor() - Method in class lejos.remote.ev3.RemoteUARTPort
 
resetSensor() - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
resetSensor() - Method in interface lejos.remote.ev3.RMIUARTPort
Reset the attached sensor.
resetSerial() - Static method in class lejos.remote.rcx.Serial
Reset the link - null
resetTachoCount() - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Resets the tachometer (encoder) count to zero at the current actuator shaft position.
resetTachoCount() - Method in class lejos.hardware.device.MMXMotor
Reset the the tachometer count.
resetTachoCount() - Method in class lejos.hardware.device.tetrix.TetrixEncoderMotor
Reset the the tachometer count.
resetTachoCount() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Reset the tachometer associated with this motor.
resetTachoCount() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
resetTachoCount() - Method in interface lejos.hardware.motor.MotorRegulator
Reset the tachometer base value, after this call the tachometer will return zero for the current position.
resetTachoCount() - Method in interface lejos.hardware.motor.Tachometer
 
resetTachoCount() - Method in class lejos.hardware.motor.UnregulatedMotor
 
resetTachoCount() - Method in class lejos.hardware.sensor.RCXRotationSensor
Reset the tacho count to zero.
resetTachoCount() - Method in class lejos.remote.ev3.RemoteMotorPort
resets the tachometer count to 0;
resetTachoCount() - Method in class lejos.remote.ev3.RemoteRequestMotorPort
 
resetTachoCount() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
resetTachoCount() - Method in interface lejos.remote.ev3.RMIMotorPort
resets the tachometer count to 0;
resetTachoCount() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
 
resetTachoCount() - Method in class lejos.remote.ev3.RMIRemoteMotorPort
 
resetTachoCount() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
resetTachoCount() - Method in class lejos.remote.nxt.RemoteNXTMotorPort
resets the tachometer count to 0;
resetTachoCount() - Method in interface lejos.robotics.Encoder
Reset the tachometer count.
resetTachoCount() - Method in interface lejos.robotics.LinearActuator
Reset the tachometer (encoder) count to zero at the current actuator position.
resetTachoCount() - Method in class lejos.robotics.MirrorMotor
 
resetTimeout() - Method in class lejos.utility.TextMenu
Reset the timeout period.
resetTo(float) - Method in class lejos.robotics.filter.IntegrationFilter
Sets the current value of the integrator to the specified value.
reshape(int, int, int, int) - Method in class lejos.robotics.geometry.RectangleInt32
Deprecated.
resize(int, int) - Method in class lejos.robotics.geometry.RectangleInt32
Deprecated.
result - Variable in class lejos.remote.ev3.EV3Reply
 
result - Variable in class lejos.remote.ev3.MenuReply
 
resume() - Method in interface lejos.remote.ev3.Menu
 
resume() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
resume() - Method in interface lejos.remote.ev3.RMIMenu
 
resumeCalibration() - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Resumes the process of updating calibration parameters after a stop.
retryCount - Variable in class lejos.hardware.sensor.I2CSensor
 
reverse - Variable in class lejos.robotics.chassis.WheeledChassis
 
reverse() - Method in class lejos.robotics.geometry.Point
same as multiply(-1);
reverseAbs - Variable in class lejos.robotics.chassis.WheeledChassis
 
RFIDSensor - Class in lejos.hardware.sensor
Support for the Codatex RFID Sensor.
RFIDSensor(I2CPort) - Constructor for class lejos.hardware.sensor.RFIDSensor
Create a class to provide access to the device.
RFIDSensor(Port) - Constructor for class lejos.hardware.sensor.RFIDSensor
Create a class to provide access to the device.
RGBMode() - Constructor for class lejos.hardware.sensor.HiTechnicColorSensor.RGBMode
 
RIGHT - Static variable in class lejos.hardware.Button
The Right button.
right - Variable in class lejos.hardware.ev3.LocalEV3
 
RIGHT - Static variable in interface lejos.hardware.Key
 
RIGHT - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Position the anchor point of text and images to the right of the text or image.
RIGHT - Static variable in class lejos.hardware.sensor.SumoEyesSensor
The Constant RIGHT (3).
RIGHT - Static variable in interface lejos.remote.ev3.RMIKey
 
rightOrth() - Method in class lejos.robotics.geometry.Point
calculate the right handed cartesian orthogonal of this poiont
RMCSentence - Class in lejos.hardware.gps
RMC is a Class designed to manage RMC Sentences from a NMEA GPS Receiver RMC - NMEA has its own version of essential gps pvt (position, velocity, time) data.
RMCSentence() - Constructor for class lejos.hardware.gps.RMCSentence
 
rmi - Variable in class lejos.remote.ev3.RemoteAnalogPort
 
rmi - Variable in class lejos.remote.ev3.RemoteI2CPort
 
rmi - Variable in class lejos.remote.ev3.RemoteMotorPort
 
rmi - Variable in class lejos.remote.ev3.RemoteUARTPort
 
RMIAnalogPort - Interface in lejos.remote.ev3
 
RMIAudio - Interface in lejos.remote.ev3
 
RMIBattery - Interface in lejos.remote.ev3
 
RMIBluetooth - Interface in lejos.remote.ev3
 
rmiEV3 - Variable in class lejos.remote.ev3.RemoteAnalogPort
 
rmiEV3 - Variable in class lejos.remote.ev3.RemoteI2CPort
 
rmiEV3 - Variable in class lejos.remote.ev3.RemoteMotorPort
 
rmiEV3 - Variable in class lejos.remote.ev3.RemotePort
 
rmiEV3 - Variable in class lejos.remote.ev3.RemoteUARTPort
 
RMIEV3 - Interface in lejos.remote.ev3
 
RMIGraphicsLCD - Interface in lejos.remote.ev3
 
RMII2CPort - Interface in lejos.remote.ev3
 
RMIKey - Interface in lejos.remote.ev3
 
RMIKeys - Interface in lejos.remote.ev3
 
RMILCD - Interface in lejos.remote.ev3
 
RMILED - Interface in lejos.remote.ev3
 
RMIMenu - Interface in lejos.remote.ev3
 
RMIMotorPort - Interface in lejos.remote.ev3
 
RMIRegulatedMotor - Interface in lejos.remote.ev3
 
RMIRemoteAnalogPort - Class in lejos.remote.ev3
 
RMIRemoteAnalogPort(String) - Constructor for class lejos.remote.ev3.RMIRemoteAnalogPort
 
RMIRemoteAudio - Class in lejos.remote.ev3
 
RMIRemoteAudio() - Constructor for class lejos.remote.ev3.RMIRemoteAudio
 
RMIRemoteBattery - Class in lejos.remote.ev3
 
RMIRemoteBattery() - Constructor for class lejos.remote.ev3.RMIRemoteBattery
 
RMIRemoteBluetooth - Class in lejos.remote.ev3
 
RMIRemoteBluetooth() - Constructor for class lejos.remote.ev3.RMIRemoteBluetooth
 
RMIRemoteEV3 - Class in lejos.remote.ev3
 
RMIRemoteEV3() - Constructor for class lejos.remote.ev3.RMIRemoteEV3
 
RMIRemoteGraphicsLCD - Class in lejos.remote.ev3
 
RMIRemoteGraphicsLCD() - Constructor for class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
RMIRemoteI2CPort - Class in lejos.remote.ev3
 
RMIRemoteI2CPort(String) - Constructor for class lejos.remote.ev3.RMIRemoteI2CPort
 
RMIRemoteKey - Class in lejos.remote.ev3
 
RMIRemoteKey() - Constructor for class lejos.remote.ev3.RMIRemoteKey
 
RMIRemoteKeys - Class in lejos.remote.ev3
 
RMIRemoteKeys() - Constructor for class lejos.remote.ev3.RMIRemoteKeys
 
RMIRemoteLCD - Class in lejos.remote.ev3
 
RMIRemoteLCD() - Constructor for class lejos.remote.ev3.RMIRemoteLCD
 
RMIRemoteLED - Class in lejos.remote.ev3
 
RMIRemoteLED() - Constructor for class lejos.remote.ev3.RMIRemoteLED
 
RMIRemoteMotorPort - Class in lejos.remote.ev3
 
RMIRemoteMotorPort(String) - Constructor for class lejos.remote.ev3.RMIRemoteMotorPort
 
RMIRemoteRegulatedMotor - Class in lejos.remote.ev3
 
RMIRemoteRegulatedMotor(String, char) - Constructor for class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
RMIRemoteSampleProvider - Class in lejos.remote.ev3
 
RMIRemoteSampleProvider(String, String, String) - Constructor for class lejos.remote.ev3.RMIRemoteSampleProvider
 
RMIRemoteTextLCD - Class in lejos.remote.ev3
 
RMIRemoteTextLCD() - Constructor for class lejos.remote.ev3.RMIRemoteTextLCD
 
RMIRemoteUARTPort - Class in lejos.remote.ev3
 
RMIRemoteUARTPort(String) - Constructor for class lejos.remote.ev3.RMIRemoteUARTPort
 
RMIRemoteWifi - Class in lejos.remote.ev3
 
RMIRemoteWifi() - Constructor for class lejos.remote.ev3.RMIRemoteWifi
 
RMISampleProvider - Interface in lejos.remote.ev3
 
RMITextLCD - Interface in lejos.remote.ev3
 
RMIUARTPort - Interface in lejos.remote.ev3
 
RMIWifi - Interface in lejos.remote.ev3
 
ROP_AND - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_AND - Static variable in class lejos.hardware.lcd.LCD
 
ROP_ANDINVERTED - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_ANDINVERTED - Static variable in class lejos.hardware.lcd.LCD
 
ROP_ANDREVERSE - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_ANDREVERSE - Static variable in class lejos.hardware.lcd.LCD
 
ROP_CLEAR - Static variable in interface lejos.hardware.lcd.CommonLCD
Common raster operations for use with bitBlt
ROP_CLEAR - Static variable in class lejos.hardware.lcd.LCD
Common raster operations for use with bitBlt
ROP_COPY - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_COPY - Static variable in class lejos.hardware.lcd.LCD
 
ROP_COPYINVERTED - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_COPYINVERTED - Static variable in class lejos.hardware.lcd.LCD
 
ROP_EQUIV - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_EQUIV - Static variable in class lejos.hardware.lcd.LCD
 
ROP_INVERT - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_INVERT - Static variable in class lejos.hardware.lcd.LCD
 
ROP_NAND - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_NAND - Static variable in class lejos.hardware.lcd.LCD
 
ROP_NOOP - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_NOOP - Static variable in class lejos.hardware.lcd.LCD
 
ROP_NOR - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_NOR - Static variable in class lejos.hardware.lcd.LCD
 
ROP_OR - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_OR - Static variable in class lejos.hardware.lcd.LCD
 
ROP_ORINVERTED - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_ORINVERTED - Static variable in class lejos.hardware.lcd.LCD
 
ROP_ORREVERSE - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_ORREVERSE - Static variable in class lejos.hardware.lcd.LCD
 
ROP_SET - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_SET - Static variable in class lejos.hardware.lcd.LCD
 
ROP_XOR - Static variable in interface lejos.hardware.lcd.CommonLCD
 
ROP_XOR - Static variable in class lejos.hardware.lcd.LCD
 
rotate(int) - Method in class lejos.hardware.device.MMXRegulatedMotor
Rotate by the requested number of degrees while blocking until completion.
rotate(int, boolean) - Method in class lejos.hardware.device.MMXRegulatedMotor
Rotate by the requested number of degrees with option for wait until completion or immediate return where the motor completes its rotation asynchronously.
rotate(int, boolean) - Method in class lejos.hardware.device.tetrix.TetrixEncoderMotor
Rotate by the requested number of degrees with option for wait until completion or immediate return where the motor completes its rotation asynchronously.
rotate(int) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
Rotate by the requested number of degrees while blocking until completion.
rotate(int, boolean) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Rotate by the request number of degrees.
rotate(int) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Rotate by the requested number of degrees.
rotate(double, boolean) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
rotate(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
rotate(int, boolean) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
rotate(int) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
rotate(int, boolean) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
causes motor to rotate through angle;
iff immediateReturn is true, method returns immediately and the motor stops by itself
If any motor method is called before the limit is reached, the rotation is canceled.
rotate(int) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Causes motor to rotate by a specified angle.
rotate(int, boolean) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
rotate(int) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
rotate(double) - Method in interface lejos.robotics.chassis.Chassis
Rotates the chassis for the specified number of degrees
rotate(double) - Method in class lejos.robotics.chassis.WheeledChassis
 
rotate(int) - Method in class lejos.robotics.MirrorMotor
 
rotate(int, boolean) - Method in class lejos.robotics.MirrorMotor
 
rotate(float, boolean) - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
robot rotates to the specified compass heading;
rotate(float) - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Rotates the NXT robot through a specific angle; Rotates left if angle is positive, right if negative, Returns when angle is reached.
rotate(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Rotates the NXT robot through a specific angle.
rotate(double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Rotates the NXT robot through a specific angle.
rotate(double) - Method in class lejos.robotics.navigation.MovePilot
 
rotate(double, boolean) - Method in class lejos.robotics.navigation.MovePilot
 
rotate(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
rotate(double, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
rotate(double) - Method in interface lejos.robotics.navigation.RotateMoveController
Rotates the NXT robot the specified number of degrees; direction determined by the sign of the parameter.
rotate(double, boolean) - Method in interface lejos.robotics.navigation.RotateMoveController
Rotates the NXT robot the specified number of degrees; direction determined by the sign of the parameter.
rotate(int, boolean) - Method in interface lejos.robotics.RegulatedMotor
causes motor to rotate through angle;
iff immediateReturn is true, method returns immediately and the motor stops by itself
If any motor method is called before the limit is reached, the rotation is canceled.
rotate(int) - Method in interface lejos.robotics.RegulatedMotor
Causes motor to rotate by a specified angle.
rotateLeft() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
rotateLeft() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
rotateLeft() - Method in class lejos.robotics.navigation.MovePilot
 
rotateLeft() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
rotateLeft() - Method in interface lejos.robotics.navigation.RotateMoveController
 
RotateMoveController - Interface in lejos.robotics.navigation
 
rotateRight() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
rotateRight() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
rotateRight() - Method in class lejos.robotics.navigation.MovePilot
 
rotateRight() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
rotateRight() - Method in interface lejos.robotics.navigation.RotateMoveController
 
rotateTo(int) - Method in class lejos.hardware.device.MMXRegulatedMotor
Rotate to the target angle while blocking until completion.
rotateTo(int, boolean) - Method in class lejos.hardware.device.MMXRegulatedMotor
Rotate to the target angle with option for wait until completion or immediate return where the motor completes its rotation asynchronously.
rotateTo(int, boolean) - Method in class lejos.hardware.device.tetrix.TetrixEncoderMotor
Rotate to the target angle with option for wait until completion or immediate return where the motor completes its rotation asynchronously.
rotateTo(int) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
Rotate to the target angle while blocking until completion.
rotateTo(int, boolean) - Method in class lejos.hardware.motor.BaseRegulatedMotor
 
rotateTo(int) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Rotate to the target angle.
rotateTo(int) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
rotateTo(int, boolean) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
rotateTo(int) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Causes motor to rotate to limitAngle;
Then getTachoCount should be within +- 2 degrees of the limit angle when the method returns
rotateTo(int, boolean) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
causes motor to rotate to limitAngle;
if immediateReturn is true, method returns immediately and the motor stops by itself
and getTachoCount should be within +- 2 degrees if the limit angle If any motor method is called before the limit is reached, the rotation is canceled.
rotateTo(int) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
rotateTo(int, boolean) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
rotateTo(int) - Method in class lejos.robotics.MirrorMotor
 
rotateTo(int, boolean) - Method in class lejos.robotics.MirrorMotor
 
rotateTo(double) - Method in class lejos.robotics.navigation.Navigator
Rotates the robot to a new absolute heading.
rotateTo(int) - Method in interface lejos.robotics.RegulatedMotor
Causes motor to rotate to limitAngle;
Then getTachoCount should be within +- 2 degrees of the limit angle when the method returns
rotateTo(int, boolean) - Method in interface lejos.robotics.RegulatedMotor
causes motor to rotate to limitAngle;
if immediateReturn is true, method returns immediately and the motor stops by itself
and getTachoCount should be within +- 2 degrees if the limit angle If any motor method is called before the limit is reached, the rotation is canceled.
rotateUpdate(float) - Method in class lejos.robotics.navigation.Pose
Rotate the heading through the specified angle
RotatingRangeScanner - Class in lejos.robotics
Implementation of RangeScanner with a rotating ultrasonic sensor or other range finder
RotatingRangeScanner(RegulatedMotor, RangeFinder) - Constructor for class lejos.robotics.RotatingRangeScanner
The constructor specifies the motor and range finder used
RotatingRangeScanner(RegulatedMotor, RangeFinder, int) - Constructor for class lejos.robotics.RotatingRangeScanner
 
rotationCount - Variable in class lejos.remote.nxt.OutputState
 
ROTATIONSPEED - Static variable in class lejos.robotics.chassis.WheeledChassis
 
rotationStarted(RegulatedMotor, int, boolean, long) - Method in class lejos.robotics.MirrorMotor
 
rotationStarted(RegulatedMotor, int, boolean, long) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
rotationStarted(RegulatedMotor, int, boolean, long) - Method in class lejos.robotics.navigation.SteeringPilot
 
rotationStarted(RegulatedMotor, int, boolean, long) - Method in interface lejos.robotics.RegulatedMotorListener
Called when the motor starts rotating.
rotationStopped(RegulatedMotor, int, boolean, long) - Method in class lejos.robotics.MirrorMotor
 
rotationStopped(RegulatedMotor, int, boolean, long) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Notify the MoveListeners when a move is completed.
rotationStopped(RegulatedMotor, int, boolean, long) - Method in class lejos.robotics.navigation.SteeringPilot
 
rotationStopped(RegulatedMotor, int, boolean, long) - Method in interface lejos.robotics.RegulatedMotorListener
Called when the motor stops rotating.
run() - Method in class lejos.hardware.gps.SimpleGPS
Keeps reading sentences from GPS receiver stream and extracting data.
run() - Method in class lejos.hardware.motor.JavaMotorRegulator.Controller
 
run() - Method in class lejos.hardware.sensor.RCXRotationSensor.Reader
Sensor reader thread.
run() - Method in class lejos.remote.nxt.LCPResponder
 
run() - Method in class lejos.robotics.navigation.Ballbot
 
RUN_PROGRAM_1 - Static variable in class lejos.hardware.device.RCXLink
 
RUN_PROGRAM_2 - Static variable in class lejos.hardware.device.RCXLink
 
RUN_PROGRAM_3 - Static variable in class lejos.hardware.device.RCXLink
 
RUN_PROGRAM_4 - Static variable in class lejos.hardware.device.RCXLink
 
RUN_PROGRAM_5 - Static variable in class lejos.hardware.device.RCXLink
 
runCommand(int) - Method in class lejos.hardware.device.PFLink
Executes a command
runMacro(int) - Method in class lejos.hardware.device.PFLink
Runs a macro which has been previously installed on the NRLink.
runMacro(int) - Method in class lejos.hardware.device.RCXLink
 
running - Variable in class lejos.remote.nxt.LCPResponder
 
runProgram(int) - Method in class lejos.hardware.device.IRLink
 
runProgram(int) - Method in interface lejos.hardware.device.IRTransmitter
 
runProgram(int) - Method in class lejos.hardware.device.RCXLink
 
runProgram(String) - Method in interface lejos.remote.ev3.Menu
 
runProgram(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
runProgram(String) - Method in interface lejos.remote.ev3.RMIMenu
 
runSample(String) - Method in interface lejos.remote.ev3.Menu
 
runSample(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
runSample(String) - Method in interface lejos.remote.ev3.RMIMenu
 
runState - Variable in class lejos.remote.nxt.OutputState
 

S

S1 - Static variable in interface lejos.hardware.port.SensorPort
 
S2 - Static variable in interface lejos.hardware.port.SensorPort
 
S3 - Static variable in interface lejos.hardware.port.SensorPort
 
S4 - Static variable in interface lejos.hardware.port.SensorPort
 
sample - Variable in class lejos.robotics.filter.PublishedSource
 
SampleBuffer - Class in lejos.robotics.filter
Provides a buffer to store samples
SampleBuffer(SampleProvider, int) - Constructor for class lejos.robotics.filter.SampleBuffer
 
SampleProvider - Interface in lejos.robotics
Abstraction for classes that fetch samples from a sensor and classes that are able to process samples.
A sample is a measurement taken by a sensor at a single moment in time.
sampleSize() - Method in class lejos.hardware.sensor.BaseSensor
 
sampleSize() - Method in class lejos.hardware.sensor.DexterIMUSensor.DexterIMUAccelerationSensor
 
sampleSize() - Method in class lejos.hardware.sensor.HiTechnicColorSensor.RGBMode
 
sampleSize() - Method in class lejos.hardware.sensor.HiTechnicEOPD.ShortDistanceMode
 
sampleSize - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
sampleSize() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
sampleSize() - Method in class lejos.hardware.sensor.NXTSoundSensor.DBMode
 
sampleSize() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor.DistanceMode
 
sampleSize() - Method in class lejos.hardware.sensor.NXTUltrasonicSensor.PingMode
 
sampleSize() - Method in class lejos.remote.ev3.RemoteRequestSampleProvider
 
sampleSize - Variable in class lejos.robotics.filter.AbstractFilter
 
sampleSize() - Method in class lejos.robotics.filter.AbstractFilter
 
sampleSize() - Method in class lejos.robotics.filter.ConcatenationFilter
 
sampleSize - Variable in class lejos.robotics.filter.PublishedSource
 
sampleSize() - Method in class lejos.robotics.filter.PublishedSource
 
sampleSize() - Method in class lejos.robotics.filter.SliceFilter
 
sampleSize() - Method in class lejos.robotics.filter.SubscribedProvider
 
sampleSize() - Method in class lejos.robotics.localization.OdometryPoseProvider
 
sampleSize() - Method in interface lejos.robotics.SampleProvider
Returns the number of elements in a sample.
The number of elements does not change during runtime.
SampleThread - Class in lejos.robotics.filter
 
SampleThread(SampleProvider, float) - Constructor for class lejos.robotics.filter.SampleThread
Create an instance and run at sampleRate.
Satellite - Class in lejos.hardware.gps
This class models data extracted from NMEA GSV Sentence $GPGSV,1,1,13,02,02,213,,03,-3,000,,11,00,121,,14,13,172,05*67 4 = SV PRN number 5 = Elevation in degrees, 90 maximum 6 = Azimuth, degrees from true north, 000 to 359 7 = SNR, 00-99 dB (null when not tracking) You can find out more about a satellite by looking up the PRN number here: http://en.wikipedia.org/wiki/List_of_GPS_satellite_launches
Satellite() - Constructor for class lejos.hardware.gps.Satellite
 
Satellite(int, int, int, int) - Constructor for class lejos.hardware.gps.Satellite
Constructor which indicate information about: PRN, Elevation, Azimuth and SNR
save(String) - Method in class lejos.robotics.filter.LinearCalibrationFilter
Stores the calibration parameters, offset and/or scale depending on current settings, to a filterProperties file.
scale - Variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
scaledValue - Variable in class lejos.remote.nxt.InputValues
The scaled value starts working after the first call to the sensor.
scan() - Method in interface lejos.robotics.objectdetection.FeatureDetector
Performs a single scan for an object and returns the results.
scan() - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
scan() - Method in class lejos.robotics.objectdetection.FusorDetector
This method scans all the sensors added to this object and returns the amalgamated results.
scan() - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
 
scan() - Method in class lejos.robotics.objectdetection.TouchFeatureDetector
 
scanLight(float, float, int, int) - Method in class lejos.robotics.LightScanner
Perform a scan for a number of light beacons within the arc defined by the start and end angles in the specified direction.
scanner - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
SCREEN_HEIGHT - Static variable in class lejos.hardware.lcd.LCD
 
SCREEN_WIDTH - Static variable in class lejos.hardware.lcd.LCD
 
scroll() - Static method in class lejos.hardware.lcd.LCD
Scrolls the screen up one text line
scroll() - Method in interface lejos.hardware.lcd.TextLCD
Scrolls the screen up one text line
scroll() - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
scroll() - Method in class lejos.remote.ev3.RemoteTextLCD
 
scroll() - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
scroll() - Method in interface lejos.remote.ev3.RMITextLCD
 
search() - Method in class lejos.hardware.LocalBTDevice
Search for and return a list of Bluetooth devices.
search() - Method in interface lejos.remote.ev3.RMIBluetooth
 
search() - Method in class lejos.remote.ev3.RMIRemoteBluetooth
 
SearchAlgorithm - Interface in lejos.robotics.pathfinding
An interface for defining generic node search algorithms.
segDist(Line) - Method in class lejos.robotics.geometry.Line
Returns the minimum distance between two line segments--this line segment and another.
segmentBlocked(DijkstraPathFinder.Node, DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for findPath().
SEL_CHAR - Static variable in class lejos.utility.TextMenu
identifies the currently selected item
select() - Method in class lejos.utility.TextMenu
Allows the user to scroll through the items, using the right and left buttons (forward and back) The Enter key closes the menu
and returns the index of the selected item.
select(int) - Method in class lejos.utility.TextMenu
Version of select without timeout
select(int, int) - Method in class lejos.utility.TextMenu
Allows the user to scroll through the items, using the right and left buttons (forward and back) The Enter key closes the menu
and returns the index of the selected item.
sendBytes(byte[], int) - Method in class lejos.hardware.device.IRLink
 
sendBytes(byte[], int) - Method in interface lejos.hardware.device.IRTransmitter
Send raw bytes to the RCX
sendBytes(byte[], int) - Method in class lejos.hardware.device.RCXLink
 
sendBytes(byte[], int) - Static method in class lejos.remote.rcx.LLC
Send a number of bytes and wait for completion of transmission
sendCmd(String) - Method in class lejos.hardware.sensor.MindsensorsBTSense
Send a command to the phone application, with a transaction id
sendCommand(char) - Method in class lejos.hardware.device.NXTCam
Send a single byte command represented by a letter
sendCommand(int, int, int) - Method in class lejos.hardware.device.RCXMotorMultiplexer
 
sendCommand(char) - Method in class lejos.hardware.sensor.MindsensorsLightSensorArray
Send a single byte command represented by a letter
sendCommand(char) - Method in class lejos.hardware.sensor.MindsensorsLineLeader
Send a single byte command represented by a letter
sendData(int, byte[], int) - Method in class lejos.hardware.sensor.I2CSensor
Executes an I2C write transaction.
sendData(int, byte[], int, int) - Method in class lejos.hardware.sensor.I2CSensor
Executes an I2C write transaction.
sendData(int, byte) - Method in class lejos.hardware.sensor.I2CSensor
Executes an I2C write transaction.
sendData(int, byte[], int, int) - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
 
sendF7(int) - Method in class lejos.hardware.device.RCXLink
 
sendMoveStart - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
sendMoveStop - Variable in class lejos.robotics.mapping.EV3NavigationModel
 
sendPacket(byte[]) - Method in class lejos.hardware.device.IRLink
 
sendPacket(byte[]) - Method in interface lejos.hardware.device.IRTransmitter
Send a packet of data to the RCX
sendPacket(byte[]) - Method in class lejos.hardware.device.RCXLink
 
sendPacket(byte[], int) - Method in class lejos.remote.rcx.LLCHandler
Send a packet.
sendPacket(byte[], int) - Method in class lejos.remote.rcx.LLCReliableHandler
Send a packet.
sendPacket(byte[], int) - Method in class lejos.remote.rcx.PacketHandler
Send a packet.
sendPacket(byte[], int, int) - Static method in class lejos.remote.rcx.Serial
Send a packet
sendPFComboDirect(int, int, int) - Method in class lejos.hardware.device.IRLink
Send commands to both motors.
sendRemoteCommand(int) - Method in class lejos.hardware.device.IRLink
 
sendRemoteCommand(int) - Method in interface lejos.hardware.device.IRTransmitter
Send a remote control command to the RCX
sendRemoteCommand(int) - Method in class lejos.hardware.device.RCXLink
 
sendRequest(byte[], int) - Method in class lejos.remote.nxt.NXTComm
 
sendRequest(byte[], int) - Method in interface lejos.remote.nxt.NXTCommRequest
Send an LCP message to the NXT and receive a reply
SENSITIVITY_BASE - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
SENSOR_PORT - Static variable in class lejos.remote.ev3.RemotePort
 
SENSOR_PORT - Static variable in class lejos.remote.ev3.RemoteRequestPort
 
SENSOR_PORT - Static variable in class lejos.remote.nxt.RemoteNXTPort
 
SensorConstants - Interface in lejos.hardware.sensor
Constants used to set Sensor types and modes.
SensorMode - Interface in lejos.hardware.sensor
 
sensorMode - Variable in class lejos.remote.nxt.InputValues
 
SensorModes - Interface in lejos.hardware.sensor
Provide access to the modes supported by a sensor
SensorMux - Class in lejos.hardware.device
 
SensorMux(I2CPort) - Constructor for class lejos.hardware.device.SensorMux
Constructor
SensorMux(Port) - Constructor for class lejos.hardware.device.SensorMux
Constructor
SensorPort - Interface in lejos.hardware.port
Basic interface for EV3 sensor ports.
SensorSelector - Class in lejos.utility
Factory for I2C sensor implementations.
SensorSelector() - Constructor for class lejos.utility.SensorSelector
 
SensorSelectorException - Exception in lejos.utility
 
SensorSelectorException(String) - Constructor for exception lejos.utility.SensorSelectorException
 
sensorType - Variable in class lejos.remote.nxt.InputValues
 
sentenceChooser(String, String) - Method in class lejos.hardware.gps.GPS
Internal helper method to aid in the subclass architecture.
sentenceChooser(String, String) - Method in class lejos.hardware.gps.SimpleGPS
Internal helper method to aid in the subclass architecture.
sentenceReceived(NMEASentence) - Method in interface lejos.hardware.gps.GPSListener
Called whenever a new NMEA sentence is produced by the GPS receiver.
Serial - Class in lejos.remote.rcx
Emulation of the RCX Serial class with Mindsensors NRLINK adapter.
SERIAL_NO - Static variable in class lejos.remote.nxt.NXTCommDevice
 
Servo - Interface in lejos.robotics
Abstraction for a range-limited servo motor.
servo1 - Variable in class lejos.hardware.device.MSC
Servo at location 1
servo2 - Variable in class lejos.hardware.device.MSC
Servo at location 2
servo3 - Variable in class lejos.hardware.device.MSC
Servo at location 3
servo4 - Variable in class lejos.hardware.device.MSC
Servo at location 4
servo5 - Variable in class lejos.hardware.device.MSC
Servo at location 5
servo6 - Variable in class lejos.hardware.device.MSC
Servo at location 6
servo7 - Variable in class lejos.hardware.device.MSC
Servo at location 7
servo8 - Variable in class lejos.hardware.device.MSC
Servo at location 8
SERVO_1 - Static variable in class lejos.hardware.device.tetrix.TetrixServoController
Represents the servo connected to Channel 1 as indicated on the controller
SERVO_2 - Static variable in class lejos.hardware.device.tetrix.TetrixServoController
Represents the servo connected to Channel 2 as indicated on the controller
SERVO_3 - Static variable in class lejos.hardware.device.tetrix.TetrixServoController
Represents the servo connected to Channel 3 as indicated on the controller
SERVO_4 - Static variable in class lejos.hardware.device.tetrix.TetrixServoController
Represents the servo connected to Channel 4 as indicated on the controller
SERVO_5 - Static variable in class lejos.hardware.device.tetrix.TetrixServoController
Represents the servo connected to Channel 5 as indicated on the controller
SERVO_6 - Static variable in class lejos.hardware.device.tetrix.TetrixServoController
Represents the servo connected to Channel 6 as indicated on the controller
set(int, int, double) - Method in class lejos.utility.Matrix
Set a single element.
SET_BRICK_NAME - Static variable in class lejos.remote.nxt.LCP
 
SET_BRICK_NAME - Static variable in interface lejos.remote.nxt.NXTProtocol
 
SET_INPUT_MODE - Static variable in class lejos.remote.nxt.LCP
 
SET_INPUT_MODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
SET_OUTPUT_STATE - Static variable in class lejos.remote.nxt.LCP
 
SET_OUTPUT_STATE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
setAcceleration(int) - Method in class lejos.hardware.device.MMXRegulatedMotor
Sets speed ramping is enabled/disabled for this motor.
setAcceleration(int) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
NOT IMPLEMENTED as the TEXTRIX motor controller does not support this command.
setAcceleration(int) - Method in class lejos.hardware.motor.BaseRegulatedMotor
sets the acceleration rate of this motor in degrees/sec/sec
The default value is 6000; Smaller values will make speeding up.
setAcceleration(int) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
setAcceleration(int) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Set the required rate of acceleration degrees/s/s
setAcceleration(int) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
setAcceleration(double, double) - Method in interface lejos.robotics.chassis.Chassis
Sets the acceleration of the chassis for the moveTo and travel methods
setAcceleration(double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setAcceleration(int) - Method in class lejos.robotics.MirrorMotor
 
setAcceleration(int) - Method in interface lejos.robotics.RegulatedMotor
Set the required rate of acceleration degrees/s/s
setAccScale(int) - Method in class lejos.hardware.sensor.CruizcoreGyro
Sets the acc scale.
setAccScale2G() - Method in class lejos.hardware.sensor.CruizcoreGyro
Sets the acceleration scale factor to 2G.
setAccScale4G() - Method in class lejos.hardware.sensor.CruizcoreGyro
Sets the acceleration scale factor to 4G.
setAccScale8G() - Method in class lejos.hardware.sensor.CruizcoreGyro
Sets the acceleration scale factor to 8G.
setAddress(int) - Method in class lejos.hardware.sensor.I2CSensor
Deprecated.
If the device has a changeable address, then constructor of the class should have an address parameter. If not, please report a bug.
setAddress(String) - Static method in class lejos.remote.nxt.NXTCommDevice
Set the USB serial number.
setADPAMode(boolean) - Method in class lejos.hardware.device.PSPNXController
Use ADPA mode only if you are trying to connect more than one I2C sensor to a single port.
setAltitude(double) - Method in class lejos.hardware.gps.Coordinates
 
setAngle(int) - Method in class lejos.hardware.device.LServo
Method to set an Angle in a RC Servo.
setAngle(int) - Method in class lejos.hardware.device.MServo
Method to set an Angle in a RC Servo.
setAngle(float) - Method in class lejos.hardware.device.tetrix.TetrixServo
Sets the angle target of the servo.
setAngle(float) - Method in interface lejos.robotics.Servo
Sets the rotational position (angle) of a ranged servo.
setAngleNoiseFactor(float) - Method in class lejos.robotics.localization.MCLParticleSet
Set the distance angle factor
setAngles(float[]) - Method in class lejos.robotics.FixedRangeScanner
 
setAngles(float[]) - Method in interface lejos.robotics.RangeScanner
Set the array of angles at which range readings are to be taken
setAngles(float[]) - Method in class lejos.robotics.RotatingRangeScanner
set the angles to be used by the getRangeValues() method
setAngularAcceleration(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
setAngularAcceleration(double) - Method in interface lejos.robotics.chassis.Chassis
Sets the angular acceleration as is used in travel, arc, rotate and setvelocity methods
setAngularAcceleration(double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setAngularAcceleration(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
setAngularAcceleration(double) - Method in class lejos.robotics.navigation.MovePilot
 
setAngularAcceleration(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
setAngularAcceleration(double) - Method in interface lejos.robotics.navigation.RotateMoveController
Sets the acceleration at which the robot will accelerate at the start of a move and decelerate at the end of a move.
setAngularSpeed(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
setAngularSpeed(double) - Method in interface lejos.robotics.chassis.Chassis
Sets the angular speed as is used in travel, arc, and rotate methods
setAngularSpeed(double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setAngularSpeed(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
sets the rotation speed of the vehicle, degrees per second
setAngularSpeed(double) - Method in class lejos.robotics.navigation.MovePilot
 
setAngularSpeed(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
setAngularSpeed(double) - Method in interface lejos.robotics.navigation.RotateMoveController
sets the rotation speed of the robot (the angular velocity of the rotate() methods)
setAPDAOff() - Method in class lejos.hardware.device.RCXLink
 
setAPDAOn() - Method in class lejos.hardware.device.RCXLink
 
setAutoRefresh(boolean) - Method in interface lejos.hardware.lcd.CommonLCD
Turn on/off the automatic refresh of the LCD display.
setAutoRefresh(boolean) - Static method in class lejos.hardware.lcd.LCD
Turn on/off the automatic refresh of the LCD display.
setAutoRefresh(boolean) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setAutoRefresh(boolean) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setAutoRefresh(boolean) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
setAutoRefresh(boolean) - Method in class lejos.remote.ev3.RemoteTextLCD
 
setAutoRefresh(boolean) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setAutoRefresh(boolean) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setAutoRefresh(boolean) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
setAutoRefresh(boolean) - Method in interface lejos.remote.ev3.RMITextLCD
 
setAutoRefreshPeriod(int) - Method in interface lejos.hardware.lcd.CommonLCD
Set the period used to perform automatic refreshing of the display.
setAutoRefreshPeriod(int) - Static method in class lejos.hardware.lcd.LCD
Set the period used to perform automatic refreshing of the display.
setAutoRefreshPeriod(int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setAutoRefreshPeriod(int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setAutoRefreshPeriod(int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
setAutoRefreshPeriod(int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
setAutoRefreshPeriod(int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setAutoRefreshPeriod(int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setAutoRefreshPeriod(int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
setAutoRefreshPeriod(int) - Method in interface lejos.remote.ev3.RMITextLCD
 
setAutoRun(boolean) - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to set auto-run on or off
setAutoSendPose(boolean) - Method in class lejos.robotics.mapping.EV3NavigationModel
Set or unset automatic sending of the robot pose to the PC when a move stops
setAzimuth(int) - Method in class lejos.hardware.gps.Satellite
Set Azimuth
setBackwardMaxSpeed(int) - Method in class lejos.hardware.device.LDCMotor
 
setBackwardMinSpeed(int) - Method in class lejos.hardware.device.LDCMotor
 
setBitRate(int) - Method in class lejos.hardware.device.UART
Set the bit rate to be used by the UART
setBitRate(int) - Method in interface lejos.hardware.port.UARTPort
Set the bit rate of the port when operating in RAW mode.
setBitRate(int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
setBitRate(int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
setBitRate(int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
setBitRate(int) - Method in interface lejos.remote.ev3.RMIUARTPort
Set the bit rate of the port when operating in RAW mode.
setBlinkingPattern(float, int) - Method in interface lejos.hardware.device.DLight
Specifies the blinking pattern of the LED.
setBlinkingPattern(int, float, int) - Method in class lejos.hardware.device.DLights
Specifies the blinking pattern of the LED.
setBorder(int) - Method in class lejos.robotics.localization.MCLParticleSet
Set border where no particles should be generated
setBounds(int, int, int, int) - Method in class lejos.robotics.geometry.RectangleInt32
Set the bounds of this rectangle
setBounds(RectangleInt32) - Method in class lejos.robotics.geometry.RectangleInt32
Set the bounds of this rectangle to the given rectangle
setByte(int, byte) - Method in interface lejos.robotics.Clock
 
setCalibrationType(int) - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
setChannel(int) - Method in class lejos.hardware.device.PFMate
Sets PF channel to use.
setChannelFour() - Method in class lejos.hardware.device.RCXSensorMultiplexer
Selects channel four
setChannelOne() - Method in class lejos.hardware.device.RCXSensorMultiplexer
Selects channel one
setChannelThree() - Method in class lejos.hardware.device.RCXSensorMultiplexer
Selects channel three
setChannelTwo() - Method in class lejos.hardware.device.RCXSensorMultiplexer
Selects channel two
setClearance(float) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Changes the safety zone between all nodes/connections and map geometry.
setClearance(float) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the clearance around the edge of the map.
setColor(int, int, int) - Method in interface lejos.hardware.device.DLight
Changes the color of the LED according to specified RGB color.
setColor(int[]) - Method in interface lejos.hardware.device.DLight
Changes the color of the LED according to specified RGB color.
setColor(int, int, int, int) - Method in class lejos.hardware.device.DLights
Changes the color of the LED according to specified RGB color.
setColor(int, int[]) - Method in class lejos.hardware.device.DLights
Changes the color of the LED according to specified RGB color.
setColor(int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Set the current drawing color.
setColor(int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Sets the current color to the specified RGB values.
setColor(int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setColor(int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setColor(int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setColor(int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setColor(int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setColor(int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setColor(int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setColor(int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setContrast(int) - Method in interface lejos.hardware.lcd.CommonLCD
Set the LCD contrast.
setContrast(int) - Static method in class lejos.hardware.lcd.LCD
Set the LCD contrast.
setContrast(int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setContrast(int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setContrast(int) - Method in class lejos.remote.ev3.RemoteRequestTextLCD
 
setContrast(int) - Method in class lejos.remote.ev3.RemoteTextLCD
 
setContrast(int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setContrast(int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setContrast(int) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
setContrast(int) - Method in interface lejos.remote.ev3.RMITextLCD
 
setControlParamaters(int, float, float, float, float, float, float, int) - Method in class lejos.hardware.motor.JavaMotorRegulator
 
setControlParamaters(int, float, float, float, float, float, float, int) - Method in interface lejos.hardware.motor.MotorRegulator
Set the motion control parameters used by the regulator.
setCurrentMode(int) - Method in class lejos.hardware.sensor.BaseSensor
 
setCurrentMode(String) - Method in class lejos.hardware.sensor.BaseSensor
 
setCurrentMode(int) - Method in interface lejos.hardware.sensor.SensorModes
Sets the current mode for fetching samples
setCurrentMode(String) - Method in interface lejos.hardware.sensor.SensorModes
Sets the current mode for fetching samples
setDate(int, int, int) - Method in interface lejos.robotics.Clock
 
setDebug(boolean) - Static method in class lejos.robotics.localization.MCLParticle
 
setDebug(boolean) - Static method in class lejos.robotics.localization.MCLParticleSet
Set system out debugging on or off
setDebug(boolean) - Method in class lejos.robotics.localization.MCLPoseProvider
Set debugging on or off
setDebug(boolean) - Method in class lejos.robotics.mapping.NavigationModel
Set debug output on of off
setDebug(boolean) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
setDefault() - Method in interface lejos.hardware.Brick
Set this brick as the default one for static methods
setDefault(Brick) - Static method in class lejos.hardware.BrickFinder
 
setDefault() - Method in class lejos.hardware.ev3.LocalEV3
 
setDefault() - Method in class lejos.remote.ev3.RemoteEV3
 
setDefault() - Method in class lejos.remote.ev3.RemoteRequestEV3
 
setDefault() - Method in class lejos.remote.nxt.RemoteNXT
 
setDefaultProgram(String) - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to set the default program
setDefaultSpeed() - Method in class lejos.hardware.device.RCXLink
 
setDegrees(float) - Method in class lejos.utility.GyroDirectionFinder
Resets the current heading to a desired value.
setDegreesCartesian(float) - Method in class lejos.utility.GyroDirectionFinder
Resets the current heading to a desired value.
setDelay(int) - Method in class lejos.hardware.device.LMotor
Set a delay in a Motor
setDelay(int) - Method in interface lejos.robotics.objectdetection.FeatureDetector
Sets the minimum delay between readings from the feature detector.
setDelay(int) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
setDelay(int) - Method in class lejos.robotics.objectdetection.FusorDetector
 
setDelay(int) - Method in class lejos.utility.DebugMessages
Set the delay measured in MS.
setDelay(int) - Method in class lejos.utility.Timer
Change the delay between timedOut messages.
setDelayEnabled(boolean) - Method in class lejos.utility.DebugMessages
Enable/Disabled if you need to show output with delay
setDigitalMode(boolean) - Method in class lejos.hardware.device.PSPNXController
 
setDirection(int, int) - Method in class lejos.hardware.device.RCXMotorMultiplexer
 
setDistanceNoiseFactor(float) - Method in class lejos.robotics.localization.MCLParticleSet
Set the distance noise factor
setDynamics(float, float) - Method in class lejos.robotics.navigation.Move
use this method to recycle an existing Move instead of creating a new one
setElevation(int) - Method in class lejos.hardware.gps.Satellite
Set Elevation
setEmissivity(float) - Method in class lejos.hardware.sensor.DexterThermalIRSensor
Set the sensor's emissivity value.
setExternalLED(int) - Method in interface lejos.hardware.device.DLight
Sets the PWM value of the external LED driver of the dLight.
setExternalLED(int, int) - Method in class lejos.hardware.device.DLights
Sets the PWM value of the external LED driver of the dLight.
setFloodlight(boolean) - Method in class lejos.hardware.sensor.EV3ColorSensor
Turns the default LED light on or off.
setFloodlight(int) - Method in class lejos.hardware.sensor.EV3ColorSensor
Used to turn on or off the floodlight by color.
setFloodlight(boolean) - Method in class lejos.hardware.sensor.NXTColorSensor
 
setFloodlight(int) - Method in class lejos.hardware.sensor.NXTColorSensor
 
setFloodlight(boolean) - Method in class lejos.hardware.sensor.NXTLightSensor
 
setFloodlight(int) - Method in class lejos.hardware.sensor.NXTLightSensor
 
setFloodlight(boolean) - Method in class lejos.hardware.sensor.RCXLightSensor
 
setFloodlight(int) - Method in class lejos.hardware.sensor.RCXLightSensor
 
setFloodlight(boolean) - Method in interface lejos.robotics.LampController
Turns the default LED light on or off.
setFloodlight(int) - Method in interface lejos.robotics.LampController
Used to turn on or off the floodlight by color.
setFont(Font) - Method in interface lejos.hardware.lcd.GraphicsLCD
Set the current font
setFont(Font) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setFont(Font) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setFont(Font) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setFont(Font) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setFont(Font) - Method in class lejos.remote.ev3.RMIRemoteTextLCD
 
setForwardMaxSpeed(int) - Method in class lejos.hardware.device.LDCMotor
 
setForwardMinSpeed(int) - Method in class lejos.hardware.device.LDCMotor
 
setFrame(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
setFrame(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D
 
setFrame(double, double, double, double) - Method in class lejos.robotics.geometry.RectangularShape
Set the frame for the rectangular shape
setFrame(Rectangle2D) - Method in class lejos.robotics.geometry.RectangularShape
Set the frame of the rectangular shape
setFriendlyName(String) - Method in class lejos.remote.nxt.NXTCommand
Set the friendly name of the NXT
setG_Score(float) - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
setGearRatio(int) - Method in class lejos.robotics.RotatingRangeScanner
Set the gear ratio
setGridSpacing(float) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Change the size of each grid square.
setGyroFilter(int) - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Set the smoothing filter for the gyro.
setH_Score(float) - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
setHeading(float) - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
sets direction of desired robot facing in degrees
setHeading(float) - Method in class lejos.robotics.navigation.Pose
 
setHeadMotor(RegulatedMotor) - Method in class lejos.robotics.RotatingRangeScanner
Set the head motor
setHigh(float) - Method in class lejos.robotics.LightDetectorAdaptor
set the value that will return 1.0 from getNormalizedLightValue()
setHighSpeed() - Method in class lejos.hardware.device.RCXLink
 
setHourMode(boolean) - Method in interface lejos.robotics.Clock
 
setHSLColor(int, int, int) - Method in interface lejos.hardware.device.DLight
Changes the color of the LED according to specified HSL color.
setHSLColor(int, int, int, int) - Method in class lejos.hardware.device.DLights
Changes the color of the LED according to specified HSL color.
setId(String) - Method in class lejos.remote.ev3.RMIRemoteKey
 
setIndex(int) - Method in class lejos.robotics.filter.FilterTerminal
 
setInitialPose(Pose, float, float) - Method in class lejos.robotics.localization.MCLPoseProvider
Generates an initial particle set in a circular normal distribution, centered on aPose.
setInitialPose(RangeReadings, float) - Method in class lejos.robotics.localization.MCLPoseProvider
Generates an initial particle set using the range readings.
setInputMode(int, int, int) - Method in class lejos.remote.nxt.NXTCommand
Tells the NXT what type of sensor you are using and the mode to operate in.
setItems(String[]) - Method in class lejos.utility.TextMenu
set the array of items to be displayed
setKeyClickLength(int) - Static method in class lejos.hardware.Button
Set the len used for key clicks
setKeyClickLength(int) - Method in interface lejos.hardware.Keys
 
setKeyClickLength(int) - Method in class lejos.remote.ev3.RemoteKeys
 
setKeyClickLength(int) - Method in class lejos.remote.ev3.RemoteRequestKeys
 
setKeyClickLength(int) - Method in interface lejos.remote.ev3.RMIKeys
 
setKeyClickLength(int) - Method in class lejos.remote.ev3.RMIRemoteKeys
 
setKeyClickTone(int, int) - Static method in class lejos.hardware.Button
Set the frequency used for a particular key.
setKeyClickTone(int, int) - Method in interface lejos.hardware.Keys
 
setKeyClickTone(int, int) - Method in class lejos.remote.ev3.RemoteKeys
 
setKeyClickTone(int, int) - Method in class lejos.remote.ev3.RemoteRequestKeys
 
setKeyClickTone(int, int) - Method in interface lejos.remote.ev3.RMIKeys
 
setKeyClickTone(int, int) - Method in class lejos.remote.ev3.RMIRemoteKeys
 
setKeyClickVolume(int) - Static method in class lejos.hardware.Button
Set the volume used for key clicks
setKeyClickVolume(int) - Method in interface lejos.hardware.Keys
 
setKeyClickVolume(int) - Method in class lejos.remote.ev3.RemoteKeys
 
setKeyClickVolume(int) - Method in class lejos.remote.ev3.RemoteRequestKeys
 
setKeyClickVolume(int) - Method in interface lejos.remote.ev3.RMIKeys
 
setKeyClickVolume(int) - Method in class lejos.remote.ev3.RMIRemoteKeys
 
setKeyClickVolume(byte) - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to set the key click volume level
setLaser(boolean) - Method in class lejos.hardware.sensor.DexterLaserSensor
 
setLatitude(double) - Method in class lejos.hardware.gps.Coordinates
 
setLCDLines(int) - Method in class lejos.utility.DebugMessages
Set the number of lines to show in the screen.
setLine(double, double, double, double) - Method in class lejos.robotics.geometry.Line2D.Double
 
setLine(float, float, float, float) - Method in class lejos.robotics.geometry.Line2D.Float
Set the float coordinates of the start and end of the line
setLine(double, double, double, double) - Method in class lejos.robotics.geometry.Line2D.Float
 
setLine(double, double, double, double) - Method in class lejos.robotics.geometry.Line2D
Sets the end points of the line using double coordinates.
setLine(Point2D, Point2D) - Method in class lejos.robotics.geometry.Line2D
Sets the end points of the line from a given start and end point
setLine(Line2D) - Method in class lejos.robotics.geometry.Line2D
Set the end points of a line to the same as a given line
setLinearAcceleration(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
setLinearAcceleration(double) - Method in interface lejos.robotics.chassis.Chassis
Sets the linear acceleration as is used in travel, arc, rotate and setvelocity methods
setLinearAcceleration(double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setLinearAcceleration(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
setLinearAcceleration(double) - Method in interface lejos.robotics.navigation.MoveController
Sets the acceleration at which the robot will accelerate at the start of a move and decelerate at the end of a move.
setLinearAcceleration(double) - Method in class lejos.robotics.navigation.MovePilot
 
setLinearAcceleration(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
setLinearAcceleration(double) - Method in class lejos.robotics.navigation.SteeringPilot
 
setLinearSpeed(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
setLinearSpeed(double) - Method in interface lejos.robotics.chassis.Chassis
Sets the linear speed as is used in travel, arc, and rotate methods
setLinearSpeed(double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setLinearSpeed(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
set travel speed in wheel diameter units per second
setLinearSpeed(double) - Method in interface lejos.robotics.navigation.MoveController
Sets the speed at which the robot will travel forward and backward (and to some extent arcs, although actual arc speed is slightly less).
setLinearSpeed(double) - Method in class lejos.robotics.navigation.MovePilot
 
setLinearSpeed(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
setLinearSpeed(double) - Method in class lejos.robotics.navigation.SteeringPilot
 
setListen(boolean) - Method in class lejos.remote.rcx.PacketHandler
Set or unset the listen flag to keep a PC serial tower alive
setLocation(double, double) - Method in class lejos.robotics.geometry.Point2D.Double
 
setLocation(double, double) - Method in class lejos.robotics.geometry.Point2D.Float
 
setLocation(float, float) - Method in class lejos.robotics.geometry.Point2D.Float
Set the location of the point
setLocation(double, double) - Method in class lejos.robotics.geometry.Point2D
Set the location of this Point2D using double coordinates
setLocation(Point2D) - Method in class lejos.robotics.geometry.Point2D
Set the location of this Point2D to the same as a specified Point2D
setLocation(int, int) - Method in class lejos.robotics.geometry.RectangleInt32
Move the rectangle to (x,y)
setLocation(Point) - Method in class lejos.robotics.geometry.RectangleInt32
Set the location of this point to the location of a given point
setLocation(Point) - Method in class lejos.robotics.navigation.Pose
Set the location of the pose
setLocation(float, float) - Method in class lejos.robotics.navigation.Pose
Sets the location of this pose to a new point at x,y;
setLongitude(double) - Method in class lejos.hardware.gps.Coordinates
 
setLongRange(boolean) - Method in class lejos.hardware.sensor.SumoEyesSensor
Enables long range of the sensor.
setLow(float) - Method in class lejos.robotics.LightDetectorAdaptor
set the value that will return 0.0 from getNormalizedLightValue()
setMap(RangeMap) - Method in class lejos.robotics.localization.MCLPoseProvider
Associates a map with the MCLPoseProvider (for example a map send from the PC).
setMap(ArrayList<Line>) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
setMap(LineMap) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
setMap(LineMap) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Feeds this class a new map.
setMap(ArrayList<Line>) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
setMap(LineMap) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
setMatrix(int, int, int, int, Matrix) - Method in class lejos.utility.Matrix
Set a submatrix.
setMatrix(int[], int[], Matrix) - Method in class lejos.utility.Matrix
Set a submatrix.
setMatrix(int[], int, int, Matrix) - Method in class lejos.utility.Matrix
Set a submatrix.
setMatrix(int, int, int[], Matrix) - Method in class lejos.utility.Matrix
Set a submatrix.
setMaxAngle(int) - Method in class lejos.hardware.device.LServo
Set Maximum angle.
setMaxDistance(float) - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
Sets the maximum distance to register detected objects from the range finder.
setMaxDistance(float) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the maximum distance between waypoints
setMaxHeadingError(double) - Method in class lejos.robotics.navigation.Waypoint
 
setMaxIterations(int) - Method in class lejos.robotics.localization.MCLParticleSet
Set the maximum iterations for the resample algorithm
setMaxIterations(int) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the maximum number of iterations before giving up when searching for a path
setMaxPositionError(double) - Method in class lejos.robotics.navigation.Waypoint
 
setMaxRange(float) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the maximum valid range readings
setMeasurementMode(int) - Method in class lejos.hardware.sensor.DexterCompassSensor
 
setMenuVersion(int, int) - Static method in class lejos.remote.nxt.LCP
Store the menu version and revision
setMinAngle(int) - Method in class lejos.hardware.device.LServo
Set Minimal angle.
setMinRadius(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
setMinRadius(double) - Method in interface lejos.robotics.navigation.ArcMoveController
Set the radius of the minimum turning circle.
setMinRadius(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Set the radius of the minimum turning circle.
setMinRadius(double) - Method in class lejos.robotics.navigation.MovePilot
 
setMinRadius(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
setMinRadius(double) - Method in class lejos.robotics.navigation.SteeringPilot
 
setMode(int) - Method in interface lejos.hardware.port.BasicSensorPort
Set the current operating mode for the sensor attached to the port.
setMode(byte) - Method in class lejos.hardware.sensor.NXTUltrasonicSensor
Sets the sensor to CONTINUOUS, PING or OFF
setMode(int) - Method in class lejos.remote.ev3.RemoteIOPort
 
setMode(int) - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
setMode(int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
setMode(int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
setMode(int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
setMode(int) - Method in interface lejos.remote.ev3.RMIUARTPort
 
setMode(int) - Method in class lejos.remote.nxt.RemoteNXTAnalogPort
Set the sensor mode
setMode(int) - Method in class lejos.remote.nxt.RemoteNXTI2CPort
Set the sensor mode
setMode(int) - Method in class lejos.remote.nxt.RemoteNXTIOPort
Set the current operating mode for the sensor attached to the port.
setModes(SensorMode[]) - Method in class lejos.hardware.sensor.BaseSensor
Define the set of modes to be made available for this sensor.
setModule(byte) - Method in class lejos.hardware.sensor.MindsensorsDistanceSensorV2
Configure the sensor for a particular Sharp Module
setMotor(int) - Method in class lejos.hardware.device.PFMate
Determines which motors are to be used buy default both are activated
setMotorPower(int, int) - Method in class lejos.hardware.device.RCXLink
 
setMotors(Matrix, Matrix, Matrix) - Method in class lejos.robotics.chassis.WheeledChassis
Utility method to set distance, speed and acceleration for each motor
setMoveDirection(int) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Sets the move direction.
setName(String) - Method in interface lejos.remote.ev3.Menu
 
setName(String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
setName(String) - Method in interface lejos.remote.ev3.RMIMenu
 
setName(String) - Static method in class lejos.remote.nxt.NXTCommDevice
Set the USB devName.
setNavMesh(NavigationMesh) - Method in class lejos.robotics.pathfinding.NodePathFinder
Method for changing the navigation mesh after this has been instantiated.
setNumReadings(int) - Method in class lejos.robotics.mapping.NavigationModel
Set the number of readings for MCL
setOccupied(int, int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
setOffsetCalibration(float) - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
setOffsetCalibration(float[]) - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
setOperatingMode(int) - Method in class lejos.hardware.sensor.DexterCompassSensor
Sets the operating mode of the sensor
setOperatingMode(int, int) - Method in class lejos.remote.nxt.RemoteNXTI2CPort
 
setOutputState(int, byte, int, int, int, int, int) - Method in class lejos.remote.nxt.NXTCommand
 
setParticles(MCLParticleSet) - Method in class lejos.robotics.localization.MCLPoseProvider
Associate a particle set with the MCLPoseProvider (e.g.
setParticleSet(MCLParticleSet) - Method in class lejos.robotics.mapping.NavigationModel
Set the MCL Particle set
setPath(Path) - Method in class lejos.robotics.navigation.Navigator
Sets the path that the Navigator will traverse.
setPattern(int) - Method in interface lejos.hardware.LED
 
setPattern(int) - Method in class lejos.remote.ev3.RemoteLED
 
setPattern(int) - Method in class lejos.remote.ev3.RemoteRequestLED
 
setPattern(int) - Method in interface lejos.remote.ev3.RMILED
 
setPattern(int) - Method in class lejos.remote.ev3.RMIRemoteLED
 
setPinMode(int) - Method in class lejos.hardware.device.PFMotorPort
 
setPinMode(int) - Method in class lejos.hardware.device.RCXPlexedMotorPort
 
setPinMode(int) - Method in interface lejos.hardware.port.IOPort
Set the port pins up ready for use.
setPinMode(int) - Method in class lejos.remote.ev3.RemoteAnalogPort
 
setPinMode(int) - Method in class lejos.remote.ev3.RemoteIOPort
 
setPinMode(int) - Method in class lejos.remote.ev3.RemoteRequestAnalogPort
 
setPinMode(int) - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
setPinMode(int) - Method in interface lejos.remote.ev3.RMIAnalogPort
 
setPinMode(int) - Method in class lejos.remote.ev3.RMIRemoteAnalogPort
 
setPinMode(int) - Method in class lejos.remote.nxt.RemoteNXTIOPort
Set the port pins up ready for use.
setPinMode(int) - Method in class lejos.remote.rcx.RCXRemoteMotorPort
 
setPixel(int, int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Method to set a pixel on the screen.
setPixel(int, int, int) - Static method in class lejos.hardware.lcd.LCD
Method to set a pixel on the screen.
setPixel(int, int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setPixel(int, int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setPixel(int, int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setPixel(int, int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setPort(I2CPort) - Static method in class lejos.remote.rcx.LLC
Set sensor port
setPort(I2CPort) - Static method in class lejos.remote.rcx.Serial
Set the sensor port
setPose(Pose) - Method in class lejos.robotics.localization.BeaconPoseProvider
 
setPose(Pose) - Method in class lejos.robotics.localization.MCLPoseProvider
set the initial pose cloud with radius noise 1 and heading noise 1
setPose(Pose) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
setPose(Pose) - Method in interface lejos.robotics.localization.PoseProvider
 
setPoseProvider(PoseProvider) - Method in class lejos.robotics.navigation.Navigator
Sets the PoseProvider after construction of the Navigator
setPoseProvider(PoseProvider) - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
 
setPower(int) - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Sets the power for the actuator.
setPower(int) - Method in class lejos.hardware.device.MMXMotor
 
setPower(int) - Method in class lejos.hardware.device.PFMateMotor
 
setPower(int) - Method in class lejos.hardware.device.tetrix.TetrixMotor
 
setPower(int) - Method in class lejos.hardware.motor.BasicMotor
 
setPower(int) - Method in interface lejos.robotics.DCMotor
Set the power level 0%-100% to be applied to the motor
setPower(int) - Method in interface lejos.robotics.LinearActuator
Set the power level 0%-100% to be applied to the actuator motor where 0% is no movement and 100% is full speed.
setPredecessor(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
set the predecessor of this node in the shortest path from the start node
setPredecessor(Node) - Method in class lejos.robotics.pathfinding.Node
Used by A* search.
setPRN(int) - Method in class lejos.hardware.gps.Satellite
Set PRN
setProperty(String, float) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
 
setPropertyArray(String, float[]) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
 
setPulse(int) - Method in class lejos.hardware.device.LMotor
This class set the Pulse over a RC Servo or a DC Motor
setPulse(int) - Method in class lejos.hardware.device.MServo
This method set the pulse in a RC Servo.
setpulseWidth(int) - Method in class lejos.hardware.device.tetrix.TetrixServo
Set the PWM pulse width for the servo.
setpulseWidth(int) - Method in interface lejos.robotics.Servo
Set the PWM pulse width for the servo.
setPWMMode(int) - Method in class lejos.hardware.device.PFMotorPort
 
setPWMMode(int) - Method in class lejos.hardware.device.RCXPlexedMotorPort
 
setPWMMode(int) - Method in interface lejos.hardware.port.BasicMotorPort
 
setPWMMode(int) - Method in class lejos.remote.ev3.RemoteMotorPort
 
setPWMMode(int) - Method in class lejos.remote.ev3.RemoteRequestMotorPort
 
setPWMMode(int) - Method in interface lejos.remote.ev3.RMIMotorPort
 
setPWMMode(int) - Method in class lejos.remote.ev3.RMIRemoteMotorPort
 
setPWMMode(int) - Method in class lejos.remote.nxt.RemoteNXTMotorPort
 
setPWMMode(int) - Method in class lejos.remote.rcx.RCXRemoteMotorPort
 
setRamping(boolean) - Method in class lejos.hardware.device.MMXMotor
Sets speed ramping is enabled/disabled for this motor.
setRandomMoveParameters(float, float) - Method in class lejos.robotics.mapping.EV3NavigationModel
Set parameters for a random move
setRange(int, int, int) - Method in class lejos.hardware.device.tetrix.TetrixServo
Set the allowable pulse width operating range of this servo in microseconds and the total travel range.
setRange(int) - Method in class lejos.hardware.sensor.DexterCompassSensor
Sets the dynamic range of the sensor (1.3 Gauss is default).
setRange(float) - Method in class lejos.hardware.sensor.DexterCompassSensor
 
setRange(int) - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Set the sensitivity used by the sensor.
setRange(int, float, float) - Method in class lejos.robotics.RangeReadings
Set the range reading
setRange(int, int, int) - Method in interface lejos.robotics.Servo
Set the allowable pulse width operating range of this servo in microseconds and the total travel range to allow the use of angle-based parameters to control the servo.
setRangeLong() - Method in class lejos.hardware.device.RCXLink
 
setRangeLong() - Static method in class lejos.remote.rcx.LLC
Sets long range transmision.
setRangeLong() - Static method in class lejos.remote.rcx.Serial
Set long range
setRangeShort() - Method in class lejos.hardware.device.RCXLink
 
setRangeShort() - Static method in class lejos.remote.rcx.LLC
Sets short range transmision.
setRangeShort() - Static method in class lejos.remote.rcx.Serial
Set short range
setRawMode() - Method in class lejos.hardware.device.RCXLink
 
setRCXRangeLong() - Method in class lejos.hardware.device.RCXLink
 
setRCXRangeShort() - Method in class lejos.hardware.device.RCXLink
 
setRect(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
setRect(Rectangle2D) - Method in class lejos.robotics.geometry.Rectangle2D.Double
 
setRect(float, float, float, float) - Method in class lejos.robotics.geometry.Rectangle2D.Float
Set the rectangle using float coordinates
setRect(Rectangle2D) - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
setRect(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D.Float
 
setRect(double, double, double, double) - Method in class lejos.robotics.geometry.Rectangle2D
Set this rectangle to a rectangle defined by double coordinates
setRect(Rectangle2D) - Method in class lejos.robotics.geometry.Rectangle2D
Set this Rectangle2D to be the same as a given Rectangle2D
setRect(double, double, double, double) - Method in class lejos.robotics.geometry.RectangleInt32
 
setReflected(boolean) - Method in class lejos.robotics.LightDetectorAdaptor
 
setRegulate(boolean) - Method in class lejos.hardware.device.MMXMotor
Disable or Enable internal motor controller speed regulation.
setRegulate(boolean) - Method in class lejos.hardware.device.tetrix.TetrixEncoderMotor
Disable or Enable internal motor controller speed regulation.
setRegulate(boolean) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
OVERRIDDEN TO NOT ALLOW CHANGE OF REGULATED STATE as the TetrixRegulatedMotor class must use regulation.
setRetryCount(int) - Method in class lejos.hardware.sensor.I2CSensor
Set the number of times that a get/send data request should be retried.
setReverse(boolean) - Method in class lejos.hardware.device.tetrix.TetrixMotor
Used to alter the forward/reverse direction mapping for the motor output.
setRobotPose(Pose) - Method in class lejos.robotics.mapping.NavigationModel
Set the current robot pose
setSampleRate(float) - Method in class lejos.hardware.sensor.DexterCompassSensor
 
setSampleRate(float) - Method in class lejos.robotics.filter.SampleThread
 
setScale(float) - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
Set the scale factor used when converting data to returned units.
setScaleCalibration(float) - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
setScaleCalibration(float, float) - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
setScaleCalibration(float[], float[]) - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
setSearchAlgorithm(SearchAlgorithm) - Method in class lejos.robotics.pathfinding.NodePathFinder
Method for changing the search algorithm after this has been instantiated.
setSendMoveStart(boolean) - Method in class lejos.robotics.mapping.EV3NavigationModel
Sets whether events are sent to the PC when a move stops
setSendMoveStop(boolean) - Method in class lejos.robotics.mapping.EV3NavigationModel
Sets whether events are sent to the PC when a move starts
setSetting(String, String) - Method in interface lejos.remote.ev3.Menu
 
setSetting(String, String) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
setSetting(String, String) - Method in interface lejos.remote.ev3.RMIMenu
 
setSigma(float) - Method in class lejos.robotics.localization.MCLParticleSet
Set the standard deviation for the sensor probability model
setSignalNoiseRatio(int) - Method in class lejos.hardware.gps.Satellite
Set SNR
setSize(int, int) - Method in class lejos.robotics.geometry.RectangleInt32
Set the size of the rectangle
setSleepTime(byte) - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to the the sleep time for the menu
setSourceDistance(float) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
set the distance of this Node from the source
setSpeed(int) - Method in class lejos.hardware.device.LDCMotor
Method to set the speed in a DC Motor
setSpeed(int) - Method in class lejos.hardware.device.MMXRegulatedMotor
Sets desired motor speed, in degrees per second.
setSpeed(int) - Method in class lejos.hardware.device.MServo
Method to set the Speed in a RC Servo.
setSpeed(int) - Method in class lejos.hardware.device.PFMateMotor
Sets the motors speed
setSpeed(int, int) - Method in class lejos.hardware.device.RCXMotorMultiplexer
 
setSpeed(int) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
Sets desired motor speed, in degrees per second.
setSpeed(int) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Sets desired motor speed , in degrees per second; The maximum reliably sustainable velocity is 100 x battery voltage under moderate load, such as a direct drive robot on the level.
setSpeed(float) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Sets desired motor speed , in degrees per second; The maximum reliably sustainable velocity is 100 x battery voltage under moderate load, such as a direct drive robot on the level.
setSpeed(int) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
setSpeed(int) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Set motor speed.
setSpeed(int) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
setSpeed(double, double) - Method in interface lejos.robotics.chassis.Chassis
Sets the speed of the chassis for the moveTo method
setSpeed(double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setSpeed(int) - Method in class lejos.robotics.LightScanner
 
setSpeed(int) - Method in class lejos.robotics.MirrorMotor
 
setSpeed(int) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
in 0.8, use setRotateSpeed() and setTravelSpeed(). The method was deprecated, as this it requires knowledge of the robots physical construction, which this interface should hide!
setSpeed(int) - Method in interface lejos.robotics.RegulatedMotor
Set motor speed.
setStallThreshold(int, int) - Method in class lejos.hardware.device.MMXRegulatedMotor
NOT IMPLEMENTED as the NXTMMX motor controller does not support this command.
setStallThreshold(int, int) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
NOT IMPLEMENTED as the TEXTRIX motor controller does not support this command.
setStallThreshold(int, int) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Set the parameters for detecting a stalled motor.
setStallThreshold(int, int) - Method in class lejos.hardware.motor.JavaMotorRegulator
 
setStallThreshold(int, int) - Method in interface lejos.hardware.motor.MotorRegulator
Set the stall detection parameters.
setStallThreshold(int, int) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
setStallThreshold(int, int) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Set the parameters for detecting a stalled motor.
setStallThreshold(int, int) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
setStallThreshold(int, int) - Method in class lejos.robotics.MirrorMotor
 
setStallThreshold(int, int) - Method in interface lejos.robotics.RegulatedMotor
Set the parameters for detecting a stalled motor.
setState(Matrix, Matrix) - Method in class lejos.utility.KalmanFilter
 
setStepTime(int) - Method in class lejos.hardware.device.tetrix.TetrixServoController
Sets the step time used for all servos on this controller.
setStrokeStyle(int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Set the stroke style to be used for drawing operations.
setStrokeStyle(int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
setStrokeStyle(int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
setStrokeStyle(int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
setStrokeStyle(int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
setTarget(Waypoint) - Method in class lejos.robotics.mapping.NavigationModel
Set the target waypoint that the robot is to go to
setTime(int, int, int) - Method in interface lejos.robotics.Clock
 
setTimeConstant(float) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Sets the time constant for the lowpass filter that is used when calibrating.
setTimeConstant(float) - Method in class lejos.robotics.filter.LowPassFilter
 
setTimeOut(int) - Method in class lejos.remote.rcx.RCXAbstractPort
Setter for property timeOut.
setTitle(String) - Method in class lejos.utility.TextMenu
set menu title.
setTracked(boolean) - Method in class lejos.hardware.gps.Satellite
 
setTrackingMode(char) - Method in class lejos.hardware.device.NXTCam
Choose either object or line tracking mode.
setType(int) - Method in interface lejos.hardware.port.BasicSensorPort
Set the operating type for the attached sensor.
setType(int) - Method in class lejos.remote.ev3.RemoteAnalogPort
 
setType(int) - Method in class lejos.remote.ev3.RemoteI2CPort
 
setType(int) - Method in class lejos.remote.ev3.RemoteIOPort
 
setType(int) - Method in class lejos.remote.ev3.RemoteRequestAnalogPort
 
setType(int) - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
setType(int) - Method in interface lejos.remote.ev3.RMII2CPort
 
setType(int) - Method in class lejos.remote.ev3.RMIRemoteI2CPort
 
setType(int) - Method in class lejos.remote.nxt.RemoteNXTAnalogPort
Set the sensor type
setType(int) - Method in class lejos.remote.nxt.RemoteNXTI2CPort
Set the sensor type
setType(int) - Method in class lejos.remote.nxt.RemoteNXTIOPort
Set the operating type for the attached sensor.
setTypeAndMode(int, int) - Method in interface lejos.hardware.port.BasicSensorPort
Deprecated.
setTypeAndMode(int, int) - Method in class lejos.remote.ev3.RemoteIOPort
 
setTypeAndMode(int, int) - Method in class lejos.remote.ev3.RemoteRequestIOPort
 
setTypeAndMode(int, int) - Method in class lejos.remote.nxt.RemoteNXTAnalogPort
Set the sensor type and mode
setTypeAndMode(int, int) - Method in class lejos.remote.nxt.RemoteNXTI2CPort
Set the sensor type and mode
setTypeAndMode(int, int) - Method in class lejos.remote.nxt.RemoteNXTIOPort
setValues(Move.MoveType, float, float, boolean) - Method in class lejos.robotics.navigation.Move
use this method to recycle an existing Move instead of creating a new one
setVelocity(double, double) - Method in interface lejos.robotics.chassis.Chassis
Moves the chassis with specified speed
setVelocity(double, double, double) - Method in interface lejos.robotics.chassis.Chassis
Moves a holonomic chassis with specified speed
setVelocity(double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setVelocity(double, double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
setVerify(boolean) - Method in class lejos.remote.nxt.NXTCommand
Toggle the verify flag.
setVisibility(boolean) - Method in class lejos.hardware.LocalBTDevice
Set the visibility state of the device
setVisibility(boolean) - Method in interface lejos.remote.ev3.RMIBluetooth
 
setVisibility(boolean) - Method in class lejos.remote.ev3.RMIRemoteBluetooth
 
setVolume(int) - Method in interface lejos.hardware.Audio
Set the master volume level
setVolume(int) - Static method in class lejos.hardware.Sound
Set the master volume level
setVolume(int) - Method in class lejos.remote.ev3.RemoteAudio
 
setVolume(int) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
setVolume(int) - Method in interface lejos.remote.ev3.RMIAudio
Set the master volume level
setVolume(int) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
setVolume(byte) - Method in class lejos.remote.nxt.NXTCommand
leJOS-specific command to set the master volume level
setVolume(int) - Method in class lejos.remote.nxt.RemoteNXTAudio
 
setWeight(float) - Method in class lejos.robotics.localization.MCLParticle
Set the weight for this particle
Shape - Interface in lejos.robotics.geometry
Shape interface without getPathIterator methods
ShapefileLoader - Class in lejos.robotics.mapping
This class loads map data from a Shapefile and produces a LineMap object, which can be used by the leJOS navigation package.
ShapefileLoader(InputStream) - Constructor for class lejos.robotics.mapping.ShapefileLoader
Creates a ShapefileLoader object using an input stream.
SHORT_RANGE_IR - Static variable in class lejos.hardware.device.RCXLink
 
ShortDistanceMode() - Constructor for class lejos.hardware.sensor.HiTechnicEOPD.ShortDistanceMode
 
ShortestPathFinder - Class in lejos.robotics.pathfinding
This class calculates the shortest path from a starting point to a finish point.
ShortestPathFinder(LineMap) - Constructor for class lejos.robotics.pathfinding.ShortestPathFinder
 
ShortestPathFinder.Node - Class in lejos.robotics.pathfinding
 
shorts - Variable in class lejos.remote.ev3.EV3Reply
 
ShortSensorMode(String, int, int, float[], float) - Constructor for class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
Internal class to provide the sensor data.
ShortSensorMode(String, int, int, float, float) - Constructor for class lejos.hardware.sensor.MindsensorsAbsoluteIMU.ShortSensorMode
 
shutdown() - Method in interface lejos.remote.ev3.Menu
 
shutdown() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
shutdown() - Method in interface lejos.remote.ev3.RMIMenu
 
shutdown() - Method in class lejos.remote.nxt.LCPResponder
Terminate the responder.
shutDown() - Method in class lejos.robotics.mapping.EV3NavigationModel
Shut down the receiver thread
signalStrength - Variable in class lejos.remote.nxt.DeviceInfo
 
SimpleGPS - Class in lejos.hardware.gps
This class manages data received from a GPS Device.
SimpleGPS(InputStream) - Constructor for class lejos.hardware.gps.SimpleGPS
The constructor.
simulateEvent(int) - Method in interface lejos.hardware.Key
 
simulateEvent(int) - Method in class lejos.remote.ev3.RemoteKey
 
simulateEvent(int) - Method in class lejos.remote.ev3.RemoteRequestKey
 
simulateEvent(int) - Method in interface lejos.remote.ev3.RMIKey
 
simulateEvent(int) - Method in class lejos.remote.ev3.RMIRemoteKey
 
singleStep(boolean) - Method in class lejos.robotics.navigation.Navigator
Controls whether the robot stops at each Waypoint; applies to the current path only.
SIZE - Static variable in class lejos.hardware.device.NXTCam
Used by sortBy() to choose sorting criteria based on size (ordered largest to smallest).
SIZE_LARGE - Static variable in class lejos.hardware.lcd.Font
 
SIZE_MEDIUM - Static variable in class lejos.hardware.lcd.Font
 
SIZE_SMALL - Static variable in class lejos.hardware.lcd.Font
 
sleep() - Method in class lejos.hardware.sensor.MindsensorsLightSensorArray
Sleep the sensor
sleep() - Method in class lejos.hardware.sensor.MindsensorsLineLeader
Sleep the sensor
SliceFilter - Class in lejos.robotics.filter
Saimple filter to take a slice of another filter
SliceFilter(SampleProvider, int, int) - Constructor for class lejos.robotics.filter.SliceFilter
 
SLOPEMASK - Static variable in interface lejos.remote.nxt.NXTProtocol
 
socket - Variable in class lejos.robotics.filter.PublishedSource
 
SOCKET_TIMEOUT - Static variable in class lejos.robotics.filter.PublishedSource
 
SocketConnection - Class in lejos.remote.nxt
 
SocketConnection(Socket) - Constructor for class lejos.remote.nxt.SocketConnection
 
SocketConnector - Class in lejos.remote.nxt
 
SocketConnector() - Constructor for class lejos.remote.nxt.SocketConnector
 
SOLID - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Constant for the SOLID stroke style.
solve(Matrix) - Method in class lejos.utility.LUDecomposition
Solve A*X = B
solve(Matrix) - Method in class lejos.utility.Matrix
Solve A*X = B
sortBy(char) - Method in class lejos.hardware.device.NXTCam
Camera sorts objects it detects according to criteria, either color, size, or no sorting at all.
Sound - Class in lejos.hardware
Class that provides access methods for the local audio device
SOUND_DB - Static variable in interface lejos.remote.nxt.NXTProtocol
 
SOUND_DBA - Static variable in interface lejos.remote.nxt.NXTProtocol
 
Sounds - Interface in lejos.hardware
 
source - Variable in class lejos.robotics.filter.AbstractFilter
 
SPECIFIED_CHANNEL_CONNECTION_IS_NOT_VALID - Static variable in class lejos.remote.nxt.ErrorMessages
Specified channel/connection is not valid
SPECIFIED_CHANNEL_CONNECTION_NOT_CONFIGURED_OR_BUSY - Static variable in class lejos.remote.nxt.ErrorMessages
Specified channel/connection not configured or busy
SPECIFIED_MAILBOX_QUEUE_IS_EMPTY - Static variable in class lejos.remote.nxt.ErrorMessages
 
speed - Variable in class lejos.hardware.motor.BaseRegulatedMotor
 
SPI_PORT - Variable in class lejos.hardware.device.LMotor
 
spinningMove(float, int, int) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Causes the robot to spin while moving along a linear path.
ss - Variable in class lejos.robotics.filter.PublishFilter
 
stallLimit - Variable in class lejos.hardware.motor.JavaMotorRegulator
 
stallTime - Variable in class lejos.hardware.motor.JavaMotorRegulator
 
start() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
start() - Method in class lejos.robotics.filter.SampleThread
Start the sampling (Default at instantiation)
start() - Method in class lejos.utility.Timer
Starts the timer, telling it to send timeOut() methods to the TimerListener.
START_CALIBRATION - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
START_PROGRAM - Static variable in class lejos.remote.nxt.LCP
 
START_PROGRAM - Static variable in interface lejos.remote.nxt.NXTProtocol
 
startBootLoader() - Method in class lejos.hardware.sensor.RFIDSensor
Enter boot loader mode.
startCalibration() - Method in class lejos.hardware.sensor.HiTechnicCompass
Starts calibration for the compass.
startCalibration() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
To calibrate Compass, mount it on your robot where it will be used and issue startCalibration method and then rotate AbsoluteIMU slowly along all three axes.
startCalibration() - Method in class lejos.hardware.sensor.MindsensorsCompass
Starts calibration for the compass.
startCalibration() - Method in interface lejos.robotics.Calibrate
Starts calibration.
startCalibration() - Method in class lejos.robotics.DirectionFinderAdapter
 
startCalibration() - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Starts a calibration proces.
startCalibration() - Method in class lejos.robotics.filter.LinearCalibrationFilter
Starts a calibration process.
startCalibration() - Method in class lejos.utility.GyroDirectionFinder
Find offset/bias of gyro while at rest (ensure it is at rest).
startContinuousRead() - Method in class lejos.hardware.sensor.RFIDSensor
Start continually reading from the device.
startDiscoveryServer(boolean) - Static method in class lejos.hardware.BrickFinder
Start the discovery server running.
startFirmware() - Method in class lejos.hardware.sensor.RFIDSensor
Start the firmware on the RFID device.
startMotor(int) - Method in class lejos.hardware.device.RCXLink
 
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.NodePathFinder
 
startPathFinding(Pose, Waypoint) - Method in interface lejos.robotics.pathfinding.PathFinder
 
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.RandomPathFinder
 
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
startProgram(String) - Method in class lejos.remote.nxt.NXTCommand
Starts a program already on the NXT.
startSingleRead() - Method in class lejos.hardware.sensor.RFIDSensor
Start a single read from the device.
startSynchronization() - Method in class lejos.hardware.device.MMXRegulatedMotor
 
startSynchronization() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
startSynchronization() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Begin a set of synchronized motor operations
startSynchronization() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
startSynchronization() - Method in interface lejos.hardware.motor.MotorRegulator
Begin a set of synchronized motor operations
startSynchronization() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
startSynchronization() - Method in class lejos.robotics.MirrorMotor
 
startSynchronization() - Method in interface lejos.robotics.RegulatedMotor
Begin a set of synchronized motor operations
status - Variable in class lejos.remote.nxt.DeviceInfo
 
status - Variable in class lejos.remote.nxt.FirmwareInfo
 
status - Variable in class lejos.remote.nxt.OutputState
 
STATUS_BUSY - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
STATUS_FAIL - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
STATUS_OK - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
STATUS_STOP - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
steer(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
steer(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Starts the robot moving forward along a curved path.
steer(double, double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Moves the robot along a curved path through a specified turn angle.
steer(double, double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Moves the robot along a curved path for a specified angle of rotation.
steer(double) - Method in interface lejos.robotics.navigation.LineFollowingMoveController
Moves the robot forward while making a curve specified by turnRate.
steer(float) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Steer.
steer(float, float) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Steer.
steer(float, float, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
Steer.
steerBackward(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Starts the robot moving backward along a curved path.
steerBackward(double) - Method in interface lejos.robotics.navigation.LineFollowingMoveController
Moves the robot backward while making a curve specified by turnRate.
SteeringPilot - Class in lejos.robotics.navigation
Vehicles that are controlled by the SteeringPilot class use a similar steering mechanism to a car, in which the front wheels pivot from side to side to control direction.
SteeringPilot(double, RegulatedMotor, RegulatedMotor, double, int, int) - Constructor for class lejos.robotics.navigation.SteeringPilot
Creates an instance of the SteeringPilot.
stop() - Method in class lejos.hardware.device.LnrActrFirgelliNXT
Immediately stop any current actuator action.
stop() - Method in class lejos.hardware.device.MMXMotor
 
stop(boolean) - Method in class lejos.hardware.device.MMXRegulatedMotor
 
stop() - Method in class lejos.hardware.device.PFMateMotor
Stops the Motor
stop() - Method in class lejos.hardware.device.tetrix.TetrixMotor
 
stop(boolean) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
stop() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Causes motor to stop, pretty much instantaneously.
stop(boolean) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Causes motor to stop, pretty much instantaneously.
stop() - Method in class lejos.hardware.motor.BasicMotor
Causes motor to stop, pretty much instantaneously.
STOP - Static variable in interface lejos.hardware.port.BasicMotorPort
Motor is stopped (PWM drive still applied)
stop() - Method in class lejos.hardware.sensor.DexterCompassSensor
 
stop() - Method in class lejos.hardware.sensor.RFIDSensor
Send a stop command to the device.
stop() - Method in class lejos.remote.ev3.RemoteRequestPilot
 
stop() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
stop(boolean) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
stop(boolean) - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Causes motor to stop, pretty much instantaneously.
stop(boolean) - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
stop() - Method in interface lejos.robotics.BaseMotor
Causes motor to stop immediately.
stop() - Method in interface lejos.robotics.chassis.Chassis
Makes the robot stop and returns immediately.
stop() - Method in class lejos.robotics.chassis.WheeledChassis
 
stop() - Method in class lejos.robotics.filter.SampleThread
Stop the sampling
stop() - Method in interface lejos.robotics.LinearActuator
Cause the actuator to stop immediately and resist any further motion.
stop(boolean) - Method in class lejos.robotics.MirrorMotor
 
stop() - Method in class lejos.robotics.MirrorMotor
 
stop() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Stops the robot soon after the method is executed.
stop() - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Stops the NXT robot.
stop() - Method in interface lejos.robotics.navigation.MoveController
Halts the NXT robot
stop() - Method in class lejos.robotics.navigation.MovePilot
 
stop() - Method in class lejos.robotics.navigation.Navigator
Stops the robot.
stop() - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
stop() - Method in class lejos.robotics.navigation.SteeringPilot
 
stop(boolean) - Method in interface lejos.robotics.RegulatedMotor
Causes motor to stop, pretty much instantaneously.
stop() - Method in class lejos.robotics.subsumption.Arbitrator
 
stop() - Method in class lejos.utility.Timer
Stops the timer.
STOP_ALL_PROGRAMS - Static variable in class lejos.hardware.device.RCXLink
 
STOP_PROGRAM - Static variable in class lejos.remote.nxt.LCP
 
STOP_PROGRAM - Static variable in interface lejos.remote.nxt.NXTProtocol
 
STOP_SOUND_PLAYBACK - Static variable in class lejos.remote.nxt.LCP
 
STOP_SOUND_PLAYBACK - Static variable in interface lejos.remote.nxt.NXTProtocol
 
stopAllPrograms() - Method in class lejos.hardware.device.IRLink
 
stopAllPrograms() - Method in interface lejos.hardware.device.IRTransmitter
 
stopAllPrograms() - Method in class lejos.hardware.device.RCXLink
 
stopCalibration() - Method in class lejos.hardware.sensor.HiTechnicCompass
Ends calibration sequence.
stopCalibration() - Method in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
Ends calibration sequence.
stopCalibration() - Method in class lejos.hardware.sensor.MindsensorsCompass
Ends calibration sequence.
stopCalibration() - Method in interface lejos.robotics.Calibrate
Ends calibration sequence.
stopCalibration() - Method in class lejos.robotics.DirectionFinderAdapter
 
stopCalibration() - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Halts the process of updating calibration parameters.
stopCalibration() - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
stopCalibration() - Method in class lejos.utility.GyroDirectionFinder
NO FUNCTIONALITY EQUIVALENT for GyroSensor so implemented just to satisfy the DirectionFinder interface.
stopDiscoveryServer() - Static method in class lejos.hardware.BrickFinder
Stop the discovery server
stopMotor(int) - Method in class lejos.hardware.device.RCXLink
 
stopMotors() - Method in class lejos.hardware.device.NXTMMX
Synchronized stop both motors
stopNow() - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
stopProgram() - Method in interface lejos.remote.ev3.Menu
 
stopProgram() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
stopProgram() - Method in interface lejos.remote.ev3.RMIMenu
 
stopProgram() - Method in class lejos.remote.nxt.NXTCommand
Forces the currently executing program to stop.
stopSoundPlayback() - Method in class lejos.remote.nxt.NXTCommand
Stops sound file playing.
Stopwatch - Class in lejos.utility
Elapsed time watch (in milliseconds)
To use - construct a new instance.
Stopwatch() - Constructor for class lejos.utility.Stopwatch
 
store(String) - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Saves the current set of calibration parameters to the file system.
storePersistentValues() - Method in class lejos.utility.PilotProps
 
str - Variable in class lejos.remote.ev3.EV3Request
 
str2 - Variable in class lejos.remote.ev3.EV3Request
 
str3 - Variable in class lejos.remote.ev3.EV3Request
 
str4 - Variable in class lejos.remote.ev3.EV3Request
 
StreamConnection - Interface in lejos.remote.nxt
This interface defines the capabilities that a stream connection must have.
stringToAddress(String) - Static method in class lejos.remote.nxt.NXTCommDevice
Convert a string version of a Bluetooth address into a byte array address.
stringToName(String) - Static method in class lejos.remote.nxt.NXTCommDevice
Convert the string version of a devName into a byte array.
stringWidth(String) - Method in class lejos.hardware.lcd.Font
Return the width of the specified string in pixels
SubscribedProvider - Class in lejos.robotics.filter
 
SubscribedProvider(DataInputStream, PublishedSource) - Constructor for class lejos.robotics.filter.SubscribedProvider
 
subscribers - Variable in class lejos.robotics.filter.PublishFilter
 
subtract(Point) - Method in class lejos.robotics.geometry.Point
Vector subtraction
subtract(float) - Method in class lejos.robotics.geometry.Point
Vector subtraction
subtractWith(Point) - Method in class lejos.robotics.geometry.Point
vector subtraction
SUCCESS - Static variable in class lejos.remote.nxt.ErrorMessages
 
sum - Variable in class lejos.robotics.filter.AbstractCalibrationFilter
 
SumFilter - Class in lejos.robotics.filter
This filter returns the sum of the N most recent samples.
The number of samples used is specified in the constructor of the filter.
SumFilter(SampleProvider, int) - Constructor for class lejos.robotics.filter.SumFilter
 
SumoEyesSensor - Class in lejos.hardware.sensor
Java class for MINDSENSORS NXT SumoEyes (triple zone IR obstacle detector).
SumoEyesSensor(AnalogPort) - Constructor for class lejos.hardware.sensor.SumoEyesSensor
Default constructor.
SumoEyesSensor(Port) - Constructor for class lejos.hardware.sensor.SumoEyesSensor
Default constructor.
suppress() - Method in interface lejos.robotics.subsumption.Behavior
The code in suppress() should cause the current behavior to exit.
suspend() - Method in interface lejos.remote.ev3.Menu
 
suspend() - Method in class lejos.remote.ev3.RemoteRequestMenu
 
suspend() - Method in interface lejos.remote.ev3.RMIMenu
 
suspendCalibration() - Method in class lejos.robotics.filter.AbstractCalibrationFilter
Halts the process of updating calibration parameters.
suspendRegulation() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Removes this motor from the motor regulation system.
SVGMapLoader - Class in lejos.robotics.mapping
This class loads map data from an SVG and produces a LineMap object, which can be used by the leJOS navigation package.
SVGMapLoader(InputStream) - Constructor for class lejos.robotics.mapping.SVGMapLoader
 
SWITCH - Static variable in interface lejos.remote.nxt.NXTProtocol
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.DexterLaserSensor
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.EV3ColorSensor
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.EV3IRSensor
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.HiTechnicEOPD
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.NXTColorSensor
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.NXTLightSensor
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.NXTSoundSensor
 
SWITCH_DELAY - Static variable in class lejos.hardware.sensor.SumoEyesSensor
 
switchMode(int, long) - Method in class lejos.hardware.sensor.UARTSensor
Switch to the selected mode (if not already in that mode) and delay for the specified period to allow the sensor to settle in the new mode.
switchType(int, long) - Method in class lejos.hardware.sensor.AnalogSensor
Switch to the selected type (if not already in that type) and delay for the specified period to allow the sensor to settle in the new state.
synchronizeWith(RegulatedMotor[]) - Method in class lejos.hardware.device.MMXRegulatedMotor
 
synchronizeWith(RegulatedMotor[]) - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
synchronizeWith(RegulatedMotor[]) - Method in class lejos.hardware.motor.BaseRegulatedMotor
Specify a set of motors that should be kept in synchronization with this one.
synchronizeWith(MotorRegulator[]) - Method in class lejos.hardware.motor.JavaMotorRegulator
 
synchronizeWith(MotorRegulator[]) - Method in interface lejos.hardware.motor.MotorRegulator
Specify a set of motors that should be kept in synchronization with this one.
synchronizeWith(RegulatedMotor[]) - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
synchronizeWith(RegulatedMotor[]) - Method in class lejos.robotics.MirrorMotor
 
synchronizeWith(RegulatedMotor[]) - Method in interface lejos.robotics.RegulatedMotor
Specify a set of motors that should be kept in synchronization with this one.
SYSTEM_COMMAND_NOREPLY - Static variable in class lejos.remote.nxt.LCP
 
SYSTEM_COMMAND_NOREPLY - Static variable in interface lejos.remote.nxt.NXTProtocol
 
SYSTEM_COMMAND_REPLY - Static variable in class lejos.remote.nxt.LCP
 
SYSTEM_COMMAND_REPLY - Static variable in interface lejos.remote.nxt.NXTProtocol
 
systemSound(int) - Method in interface lejos.hardware.Audio
Play a system sound.
systemSound(boolean, int) - Static method in class lejos.hardware.Sound
Play a system sound.
systemSound(int) - Method in class lejos.remote.ev3.RemoteAudio
 
systemSound(int) - Method in class lejos.remote.ev3.RemoteRequestAudio
 
systemSound(int) - Method in interface lejos.remote.ev3.RMIAudio
Play a system sound.
systemSound(int) - Method in class lejos.remote.ev3.RMIRemoteAudio
 
systemSound(int) - Method in class lejos.remote.nxt.RemoteNXTAudio
 

T

t - Static variable in class lejos.hardware.lcd.LCD
 
T1 - Variable in class lejos.hardware.device.TouchMUX
Instance for the touch sensor connected to port T1
T2 - Variable in class lejos.hardware.device.TouchMUX
Instance for the touch sensor connected to port T2
T3 - Variable in class lejos.hardware.device.TouchMUX
Instance for the touch sensor connected to port T3
tachoAtMoveStart - Variable in class lejos.robotics.chassis.WheeledChassis
 
tachoCount - Variable in class lejos.remote.nxt.OutputState
 
TACHOCOUNT - Static variable in class lejos.robotics.chassis.WheeledChassis
 
tachoLimit - Variable in class lejos.remote.nxt.OutputState
 
Tachometer - Interface in lejos.hardware.motor
Abstraction for the tachometer built into NXT motors.
Tachometer - Interface in lejos.robotics
Abstraction for a Tachometer, which monitors speed of the encoder.
TachoMotorPort - Interface in lejos.hardware.port
Abstraction for a motor port that supports NXT motors with tachometers.
tachoPort - Variable in class lejos.hardware.motor.BaseRegulatedMotor
 
tachoPort - Variable in class lejos.hardware.motor.JavaMotorRegulator
 
takeControl() - Method in interface lejos.robotics.subsumption.Behavior
The boolean return indicates if this behavior should seize control of the robot.
target - Variable in class lejos.robotics.mapping.NavigationModel
 
TEMPERATURE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
test() - Method in class lejos.hardware.sensor.DexterCompassSensor
Self-test routine of the sensor.
TetrixControllerFactory - Class in lejos.hardware.device.tetrix
HiTechnic Tetrix Motor and Servo Controller factory class used to provide Motor and Servo controller abstractions.
TetrixControllerFactory(Port) - Constructor for class lejos.hardware.device.tetrix.TetrixControllerFactory
Instantiate a TetrixControllerFactory using the specified NXT sensor port.
TetrixEncoderMotor - Class in lejos.hardware.device.tetrix
Tetrix DC motor abstraction with encoder support.
TetrixMotor - Class in lejos.hardware.device.tetrix
Tetrix basic DC motor abstraction without encoder support.
TetrixMotorController - Class in lejos.hardware.device.tetrix
HiTechnic Tetrix Motor Controller abstraction.
TetrixMotorController(I2CPort, int) - Constructor for class lejos.hardware.device.tetrix.TetrixMotorController
Instantiate a HiTechnic TETRIX Motor Controller connected to the given port and daisy chain position.
TetrixRegulatedMotor - Class in lejos.hardware.device.tetrix
Tetrix DC motor abstraction with encoder support that implements RegulatedMotor.
TetrixServo - Class in lejos.hardware.device.tetrix
Basic servo motor abstraction.
TetrixServoController - Class in lejos.hardware.device.tetrix
HiTechnic Servo Controller abstraction.
TetrixServoController(I2CPort, int) - Constructor for class lejos.hardware.device.tetrix.TetrixServoController
Instantiate for a HiTechnic TETRIX Servo Controller connected to the given port and daisy chain position.
textLCD - Variable in class lejos.hardware.ev3.LocalEV3
 
TextLCD - Interface in lejos.hardware.lcd
 
TextMenu - Class in lejos.utility
Displays a list of items.
TextMenu(String[]) - Constructor for class lejos.utility.TextMenu
This constructor sets location of the top row of the item list to row 0 of the display.
TextMenu(String[], int) - Constructor for class lejos.utility.TextMenu
This constructor allows specification location of the item list .
TextMenu(String[], int, String) - Constructor for class lejos.utility.TextMenu
This constuctor allows the specfication of a title (of up to 16 characters) and the location of the item list
The title is displayed in the row above the item list.
timedOut() - Method in interface lejos.utility.TimerListener
Called every time the Timer fires.
Timer - Class in lejos.utility
Timer object, with some similar functionality to java.Swing.Timer.
Timer(int, TimerListener) - Constructor for class lejos.utility.Timer
Create a Timer object.
TimerListener - Interface in lejos.utility
Listener used with Timer.
times(double) - Method in class lejos.utility.Matrix
Multiply a matrix by a scalar, C = s*A
times(Matrix) - Method in class lejos.utility.Matrix
Linear algebraic matrix multiplication, A * B
timesEquals(double) - Method in class lejos.utility.Matrix
Multiply a matrix by a scalar in place, A = s*A
timeStamp - Variable in class lejos.robotics.filter.PublishedSource
 
toCartesianMatrix(double, double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
toMatrix(double, double, double) - Method in class lejos.robotics.chassis.WheeledChassis
Create a Matrix to store linear and angular components
TOP - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Position the anchor point of text and images above the text or image.
toPolar(double, double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
TOSI - Static variable in class lejos.hardware.sensor.DexterIMUSensor.DexterIMUAccelerationSensor
 
toString() - Method in interface lejos.hardware.port.UARTPort
Return the current sensor reading to a string.
toString() - Method in class lejos.remote.ev3.RemoteUARTPort
 
toString() - Method in class lejos.robotics.filter.LinearCalibrationFilter
 
toString() - Method in class lejos.robotics.geometry.Point2D.Double
Represent the Point2D.Double as a String
toString() - Method in class lejos.robotics.geometry.Point2D.Float
Represent the Point2SD.Float as a String
toString() - Method in class lejos.robotics.geometry.RectangleInt32
Returns a String representing this rectangle.
toString() - Method in class lejos.robotics.navigation.Move
 
toString() - Method in class lejos.robotics.navigation.Pose
return string contains x,y and heading
toString() - Method in class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
toString() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
toString() - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
toStringValue() - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
toStringValue() - Method in interface lejos.remote.ev3.RMIUARTPort
Return the current sensor reading to a string.
Touch - Interface in lejos.robotics
Abstraction for touch sensors
TouchAdapter - Class in lejos.robotics
 
TouchAdapter(BaseSensor) - Constructor for class lejos.robotics.TouchAdapter
 
TouchFeatureDetector - Class in lejos.robotics.objectdetection
This class allows a touch sensor to be used as a defacto range sensor by reporting the position of the touch sensor to the object detection API.
TouchFeatureDetector(Touch) - Constructor for class lejos.robotics.objectdetection.TouchFeatureDetector
Creates a touch detector in which the touch sensor is assumed to be situated in the center of the robot.
TouchFeatureDetector(Touch, double, double) - Constructor for class lejos.robotics.objectdetection.TouchFeatureDetector
If you want the bumpers to report contact relative to the geometry of where they are placed on the robot, you can provide the x, y offsets of each bumper relative to the center of the robot (the center is the halfway point between the drive wheels).
TouchMUX - Class in lejos.hardware.device
Interface for the Mindsensors Touch Multiplexer.
TouchMUX(AnalogPort) - Constructor for class lejos.hardware.device.TouchMUX
Create a object to provide access to a touch sensor multiplexer
TouchMUX(Port) - Constructor for class lejos.hardware.device.TouchMUX
Create a object to provide access to a touch sensor multiplexer
trace() - Method in class lejos.utility.Matrix
Matrix trace.
TRANS_MIRROR - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANS_MIRROR_ROT180 - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANS_MIRROR_ROT270 - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANS_MIRROR_ROT90 - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANS_NONE - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANS_ROT180 - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANS_ROT270 - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANS_ROT90 - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
TRANSITIONCNTMODE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
translate(int, int) - Method in interface lejos.hardware.lcd.GraphicsLCD
Translates the origin of the graphics context to the point (x, y) in the current coordinate system.
translate(int, int) - Method in class lejos.remote.ev3.RemoteGraphicsLCD
 
translate(int, int) - Method in class lejos.remote.ev3.RemoteRequestGraphicsLCD
 
translate(int, int) - Method in interface lejos.remote.ev3.RMIGraphicsLCD
 
translate(int, int) - Method in class lejos.remote.ev3.RMIRemoteGraphicsLCD
 
translate(float, float) - Method in class lejos.robotics.geometry.Point
Translates this point, at location (x, y), by dx along the x axis and dy along the y axis so that it now represents the point (x + dx, y + dy).
translate(float, float) - Method in class lejos.robotics.navigation.Pose
Change the x and y coordinates of the pose by adding dx and dy.
Transmittable - Interface in lejos.robotics
 
transpose() - Method in class lejos.utility.Matrix
Matrix transpose.
travel(double, boolean) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
travel(double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
travel(double) - Method in interface lejos.robotics.chassis.Chassis
Moves the chassis the specified distance
travel(double) - Method in class lejos.robotics.chassis.WheeledChassis
 
travel(float, boolean) - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Moves the NXT robot a specific distance.
travel(float) - Method in class lejos.robotics.navigation.CompassPilot
Deprecated.
Moves the NXT robot a specific distance;
A positive distance causes forward motion; negative distance moves backward.
travel(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward.
travel(double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward.
travel(double) - Method in interface lejos.robotics.navigation.MoveController
Moves the NXT robot a specific distance.
travel(double, boolean) - Method in interface lejos.robotics.navigation.MoveController
Moves the NXT robot a specific distance.
travel(double) - Method in class lejos.robotics.navigation.MovePilot
 
travel(double, boolean) - Method in class lejos.robotics.navigation.MovePilot
 
travel(double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
travel(double, double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
This method causes the robot to travel in a linear path, similar to other travel() methods, except you can specify which direction to move (relative to the current robot heading).
travel(double, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
travel(double, double, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
This method causes the robot to travel in a linear path, similar to other travel() methods, except you can specify which direction to move (relative to the current robot heading).
travel(double) - Method in class lejos.robotics.navigation.SteeringPilot
 
travel(double, boolean) - Method in class lejos.robotics.navigation.SteeringPilot
 
travelArc(double, double, boolean) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
travelArc(double, double) - Method in class lejos.remote.ev3.RemoteRequestPilot
 
travelArc(double, double) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving.
travelArc(double, double, boolean) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving.
travelArc(double, double) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
travelArc(double, double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
travelArc(double, double) - Method in class lejos.robotics.navigation.MovePilot
 
travelArc(double, double, boolean) - Method in class lejos.robotics.navigation.MovePilot
 
travelArc(double, double) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
travelArc(double, double, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
 
travelArc(double, double, float) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
This method moves the robot in an arc, similar to the other OmniPilot.travelArc(double, double) methods, except you can choose any of the 360 degree directions relative to the current heading (0) of the robot, while keeping the heading of the robot pointed in the same direction during the move.
travelArc(double, double, float, boolean) - Method in class lejos.robotics.navigation.OmniPilot
Deprecated.
This method moves the robot in an arc, similar to the other OmniPilot.travelArc(double, double) methods, except you can choose any of the 360 degree directions relative to the current heading (0) of the robot, while keeping the heading of the robot pointed in the same direction during the move.
travelArc(double, double) - Method in class lejos.robotics.navigation.SteeringPilot
 
travelArc(double, double, boolean) - Method in class lejos.robotics.navigation.SteeringPilot
 
travelCartesian(double, double, double) - Method in interface lejos.robotics.chassis.Chassis
Moves a holonomic robot with the specified speed.
travelCartesian(double, double, double) - Method in class lejos.robotics.chassis.WheeledChassis
 
turnRatio - Variable in class lejos.remote.nxt.OutputState
 
twoBeeps() - Static method in class lejos.hardware.Sound
Beeps twice.
typ - Variable in class lejos.remote.ev3.RemoteIOPort
 
typ - Variable in class lejos.remote.ev3.RemotePort
 
typ - Variable in class lejos.remote.ev3.RemoteRequestIOPort
 
typ - Variable in class lejos.remote.ev3.RemoteRequestPort
 
typ - Variable in class lejos.remote.nxt.RemoteNXTIOPort
 
typ - Variable in class lejos.remote.nxt.RemoteNXTPort
 
TYPE_ANGLE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_COLORBLUE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_COLORFULL - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_COLORGREEN - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_COLORNONE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_COLORRED - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_CUSTOM - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_DIFFERENTIAL - Static variable in class lejos.robotics.chassis.WheeledChassis
 
TYPE_ERROR - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_HIGHSPEED - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_HIGHSPEED_9V - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_HISPEED - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_HOLONOMIC - Static variable in class lejos.robotics.chassis.WheeledChassis
 
TYPE_IIC_UNKNOWN - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_LIGHT_ACTIVE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_LIGHT_INACTIVE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_LOWSPEED - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_LOWSPEED_9V - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_MINITACHO - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NEWTACHO - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NO_SENSOR - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_NONE - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NXT_COLOR - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NXT_IIC - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NXT_LIGHT - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NXT_SOUND - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NXT_TEST - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_NXT_TOUCH - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_REFLECTION - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_SOUND_DB - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_SOUND_DBA - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_SWITCH - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_TACHO - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_TEMPERATURE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
TYPE_TERMINAL - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_THIRD_PARTY_END - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_THIRD_PARTY_START - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
TYPE_UNKNOWN - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 

U

UART - Class in lejos.hardware.device
This class provides low level access to a UART device.
UART(Port) - Constructor for class lejos.hardware.device.UART
Create a UART device attached to the specified port.
UART.UARTInputStream - Class in lejos.hardware.device
internal class that provides an InputStream interface to a UART
UART.UARTOutputStream - Class in lejos.hardware.device
internal class that provides an OutputStream interface to a UART
UART_MAX_MODES - Static variable in interface lejos.hardware.sensor.EV3SensorConstants
 
UART_RAW_MODE - Static variable in interface lejos.hardware.port.UARTPort
 
UARTInputStream() - Constructor for class lejos.hardware.device.UART.UARTInputStream
 
UARTOutputStream() - Constructor for class lejos.hardware.device.UART.UARTOutputStream
 
UARTPort - Interface in lejos.hardware.port
 
UARTSensor - Class in lejos.hardware.sensor
Base class for EV3 UART based sensors.
UARTSensor(UARTPort) - Constructor for class lejos.hardware.sensor.UARTSensor
Standard constructor for a UARTSensor initialises things and places the device into mode 0.
UARTSensor(Port) - Constructor for class lejos.hardware.sensor.UARTSensor
Standard constructor for a UARTSensor initialises things and places the device into mode 0.
UARTSensor(UARTPort, int) - Constructor for class lejos.hardware.sensor.UARTSensor
Create the sensor object and switch to the selected mode
UARTSensor(Port, int) - Constructor for class lejos.hardware.sensor.UARTSensor
Create the sensor object and switch to the selected mode
UDP_PERIOD - Static variable in class lejos.robotics.filter.PublishFilter
 
uminus() - Method in class lejos.utility.Matrix
Unary minus
UNDEFINED_ERROR - Static variable in class lejos.remote.nxt.ErrorMessages
 
UNKNOWN_COMMAND_OPCODE - Static variable in class lejos.remote.nxt.ErrorMessages
 
unload() - Method in class lejos.hardware.device.LMotor
 
unloadAllServos() - Method in class lejos.hardware.device.LSC
Unload all servos connected in a LSC
UnregulatedMotor - Class in lejos.hardware.motor
Abstraction for an NXT motor with no speed regulation.
UnregulatedMotor(Port, int) - Constructor for class lejos.hardware.motor.UnregulatedMotor
Create an instance of a NXTMotor using the specified motor port and PWM operating mode.
UnregulatedMotor(Port) - Constructor for class lejos.hardware.motor.UnregulatedMotor
Create an instance of a NXTMotor using the specified motor port the PWM operating mode will be PWM_BREAK BasicMotorPort.PWM_BRAKE
UnregulatedMotor(TachoMotorPort, int) - Constructor for class lejos.hardware.motor.UnregulatedMotor
Create an instance of a NXTMotor using the specified motor port and PWM operating mode.
UnregulatedMotor(TachoMotorPort) - Constructor for class lejos.hardware.motor.UnregulatedMotor
Create an instance of a NXTMotor using the specified motor port the PWM operating mode will be PWM_BREAK BasicMotorPort.PWM_BRAKE
UP - Static variable in class lejos.hardware.Button
The Up button.
up - Variable in class lejos.hardware.ev3.LocalEV3
 
UP - Static variable in interface lejos.hardware.Key
 
UP - Static variable in interface lejos.remote.ev3.RMIKey
 
update() - Method in class lejos.hardware.device.PFMate
Sends command to PF IR receiver to apply changes made to the registers.
update() - Method in class lejos.robotics.localization.MCLPoseProvider
Calls range scanner to get range readings, calculates the probabilities of each particle from the range readings and the map and calls resample(()
update(RangeReadings) - Method in class lejos.robotics.localization.MCLPoseProvider
Calculates particle weights from readings, then resamples the particle set;
update(Matrix, Matrix) - Method in class lejos.utility.KalmanFilter
 
UPDATE_TIME - Static variable in class lejos.hardware.sensor.RCXRotationSensor
 
updateMsg(int, String, String) - Static method in class lejos.remote.nxt.LCP
Update a message in the inbox, or add a new one if no match
updateState(int) - Method in class lejos.hardware.motor.BasicMotor
Update the internal state tracking the motor direction
updateState(int, boolean, boolean) - Method in class lejos.hardware.motor.JavaMotorRegulator
Update the internal state of the motor.
uploadFile(String, byte[]) - Method in interface lejos.remote.ev3.Menu
 
uploadFile(String, byte[]) - Method in class lejos.remote.ev3.RemoteRequestMenu
 
uploadFile(String, byte[]) - Method in interface lejos.remote.ev3.RMIMenu
 
uploadFile(File, String) - Method in class lejos.remote.nxt.NXTCommand
Upload a file to the NXT
usDelay(long) - Static method in class lejos.utility.Delay
Wait for the specified number of microseconds.

V

valid - Variable in class lejos.remote.nxt.InputValues
NXT indicates if it thinks the data is valid
VALID_TIME - Static variable in class lejos.hardware.device.DeviceIdentifier
 
value - Variable in class lejos.remote.ev3.EV3Reply
 
value - Variable in class lejos.remote.ev3.MenuReply
 
value - Variable in class lejos.remote.ev3.MenuRequest
 
valueOf(String) - Static method in enum lejos.remote.ev3.EV3Request.Request
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum lejos.remote.ev3.MenuRequest.Request
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum lejos.robotics.mapping.NavigationModel.NavEvent
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum lejos.robotics.navigation.Move.MoveType
Returns the enum constant of this type with the specified name.
values() - Static method in enum lejos.remote.ev3.EV3Request.Request
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum lejos.remote.ev3.MenuRequest.Request
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum lejos.robotics.mapping.NavigationModel.NavEvent
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum lejos.robotics.navigation.Move.MoveType
Returns an array containing the constants of this enum type, in the order they are declared.
VCENTER - Static variable in interface lejos.hardware.lcd.GraphicsLCD
Centering images vertically around the anchor point.
VERY_HIGH - Static variable in class lejos.hardware.sensor.MindsensorsAbsoluteIMU
 
video - Variable in class lejos.hardware.ev3.LocalEV3
 
Video - Interface in lejos.hardware.video
 
VideoUtils - Class in lejos.hardware.video
 
VideoUtils() - Constructor for class lejos.hardware.video.VideoUtils
 
VOL_MAX - Static variable in interface lejos.hardware.Sounds
 
VOL_SETTING - Static variable in class lejos.hardware.Button
 
VOL_SETTING - Static variable in interface lejos.hardware.Keys
 
VOL_SETTING - Static variable in class lejos.hardware.Sound
 
VOLT_DATA_LSB - Static variable in class lejos.hardware.sensor.MindsensorsDistanceSensorV2
 
vtgSentence - Variable in class lejos.hardware.gps.SimpleGPS
 
VTGSentence - Class in lejos.hardware.gps
VTGSentence is a Class designed to manage VTG Sentences from a NMEA GPS Receiver $GPVTG Track Made Good and Ground Speed.
VTGSentence() - Constructor for class lejos.hardware.gps.VTGSentence
 

W

waitComplete() - Method in class lejos.hardware.device.MMXRegulatedMotor
 
waitComplete() - Method in class lejos.hardware.device.tetrix.TetrixRegulatedMotor
 
waitComplete() - Method in class lejos.hardware.motor.BaseRegulatedMotor
Wait until the current movement operation is complete (this can include the motor stalling).
waitComplete() - Method in class lejos.hardware.motor.JavaMotorRegulator
 
waitComplete() - Method in interface lejos.hardware.motor.MotorRegulator
Wait until the current movement operation is complete (this can include the motor stalling).
waitComplete() - Method in class lejos.remote.ev3.RemoteRequestRegulatedMotor
 
waitComplete() - Method in interface lejos.remote.ev3.RMIRegulatedMotor
Wait until the current movement operation is complete (this can include the motor stalling).
waitComplete() - Method in class lejos.remote.ev3.RMIRemoteRegulatedMotor
 
waitComplete() - Method in interface lejos.robotics.chassis.Chassis
Blocks while the chassis is moving, returns when all wheels have stopped (including stops caused by stalls)
waitComplete() - Method in class lejos.robotics.chassis.WheeledChassis
 
waitComplete() - Method in class lejos.robotics.MirrorMotor
 
waitComplete() - Method in interface lejos.robotics.RegulatedMotor
Wait until the current movement operation is complete (this can include the motor stalling).
waitConnect() - Method in class lejos.remote.nxt.LCPResponder
Method called when the responder is waiting for a new connection.
waitForAnyEvent() - Static method in class lejos.hardware.Button
Waits for some button to be pressed or released.
waitForAnyEvent(int) - Static method in class lejos.hardware.Button
Waits for some button to be pressed or released.
waitForAnyEvent() - Method in class lejos.hardware.device.MindSensorsNumPad
Waits for some button to be pressed or released.
waitForAnyEvent(int) - Method in class lejos.hardware.device.MindSensorsNumPad
Waits for some button to be pressed or released.
waitForAnyEvent() - Method in interface lejos.hardware.Keys
 
waitForAnyEvent(int) - Method in interface lejos.hardware.Keys
 
waitForAnyEvent() - Method in class lejos.remote.ev3.RemoteKeys
 
waitForAnyEvent(int) - Method in class lejos.remote.ev3.RemoteKeys
 
waitForAnyEvent() - Method in class lejos.remote.ev3.RemoteRequestKeys
 
waitForAnyEvent(int) - Method in class lejos.remote.ev3.RemoteRequestKeys
 
waitForAnyEvent() - Method in interface lejos.remote.ev3.RMIKeys
 
waitForAnyEvent(int) - Method in interface lejos.remote.ev3.RMIKeys
 
waitForAnyEvent() - Method in class lejos.remote.ev3.RMIRemoteKeys
 
waitForAnyEvent(int) - Method in class lejos.remote.ev3.RMIRemoteKeys
 
waitForAnyPress(int) - Static method in class lejos.hardware.Button
Waits for some button to be pressed.
waitForAnyPress() - Static method in class lejos.hardware.Button
Waits for some button to be pressed.
waitForAnyPress() - Method in class lejos.hardware.device.MindSensorsNumPad
Waits for some button to be pressed.
waitForAnyPress(int) - Method in class lejos.hardware.device.MindSensorsNumPad
Waits for some button to be pressed.
waitForAnyPress(int) - Method in interface lejos.hardware.Keys
 
waitForAnyPress() - Method in interface lejos.hardware.Keys
 
waitForAnyPress(int) - Method in class lejos.remote.ev3.RemoteKeys
 
waitForAnyPress() - Method in class lejos.remote.ev3.RemoteKeys
 
waitForAnyPress(int) - Method in class lejos.remote.ev3.RemoteRequestKeys
 
waitForAnyPress() - Method in class lejos.remote.ev3.RemoteRequestKeys
 
waitForAnyPress(int) - Method in interface lejos.remote.ev3.RMIKeys
 
waitForAnyPress() - Method in interface lejos.remote.ev3.RMIKeys
 
waitForAnyPress(int) - Method in class lejos.remote.ev3.RMIRemoteKeys
 
waitForAnyPress() - Method in class lejos.remote.ev3.RMIRemoteKeys
 
waitForConnection(int, int) - Method in class lejos.remote.nxt.BTConnector
 
waitForConnection(int, int) - Method in class lejos.remote.nxt.NXTCommConnector
Wait for an incoming connection, or for the request to timeout.
waitForConnection(int, int) - Method in class lejos.remote.nxt.SocketConnector
 
waitForPress() - Method in interface lejos.hardware.Key
 
waitForPress() - Method in class lejos.remote.ev3.RemoteKey
 
waitForPress() - Method in class lejos.remote.ev3.RemoteRequestKey
 
waitForPress() - Method in interface lejos.remote.ev3.RMIKey
 
waitForPress() - Method in class lejos.remote.ev3.RMIRemoteKey
 
waitForPressAndRelease() - Method in interface lejos.hardware.Key
 
waitForPressAndRelease() - Method in class lejos.remote.ev3.RemoteKey
 
waitForPressAndRelease() - Method in class lejos.remote.ev3.RemoteRequestKey
 
waitForPressAndRelease() - Method in interface lejos.remote.ev3.RMIKey
 
waitForPressAndRelease() - Method in class lejos.remote.ev3.RMIRemoteKey
 
waitForStop() - Method in class lejos.robotics.navigation.Navigator
Waits for the robot to stop for any reason ; returns true if the robot stopped at the final Waypoint of the path.
waitTillSent() - Static method in class lejos.remote.rcx.Serial
Wait until the packet is sent - null
waitValid() - Method in class lejos.hardware.device.DeviceIdentifier
Wait until the identification data for this port is valid
wakeUp() - Method in class lejos.hardware.sensor.MindsensorsLightSensorArray
Wake up the sensor
wakeUp() - Method in class lejos.hardware.sensor.MindsensorsLineLeader
Wake up the sensor
wakeUp() - Method in class lejos.hardware.sensor.RFIDSensor
The sensor will go into a power save mode after a short time.
Waypoint - Class in lejos.robotics.navigation
A sequence of way points make up a route that a robot can navigate.
Waypoint(double, double) - Constructor for class lejos.robotics.navigation.Waypoint
 
Waypoint(double, double, double) - Constructor for class lejos.robotics.navigation.Waypoint
 
Waypoint(Point) - Constructor for class lejos.robotics.navigation.Waypoint
 
Waypoint(Pose) - Constructor for class lejos.robotics.navigation.Waypoint
 
WaypointListener - Interface in lejos.robotics.navigation
Interface for informing listeners that a way point has been generated.
Wheel - Interface in lejos.robotics.chassis
 
WHEEL_SIZE_EV3 - Static variable in interface lejos.robotics.navigation.MoveController
EV3 kit wheel diameter, in centimeters
WHEEL_SIZE_NXT1 - Static variable in interface lejos.robotics.navigation.MoveController
NXT 1.0 kit wheel diameter, in centimeters
WHEEL_SIZE_NXT2 - Static variable in interface lejos.robotics.navigation.MoveController
NXT 2.0 kit wheel diameter, in centimeters
WHEEL_SIZE_RCX - Static variable in interface lejos.robotics.navigation.MoveController
White RCX "motorcycle" wheel diameter, in centimeters
WheeledChassis - Class in lejos.robotics.chassis
Represents the chassis of a wheeled robot.
WheeledChassis(Wheel[], int) - Constructor for class lejos.robotics.chassis.WheeledChassis
 
WheeledChassis.HolonomicModeler - Class in lejos.robotics.chassis
The Modeler class helps to model a wheel.
WheeledChassis.Modeler - Class in lejos.robotics.chassis
The Modeler class helps to model a wheel.
whenConnected() - Method in interface lejos.robotics.mapping.NavEventListener
 
WHITE - Static variable in interface lejos.hardware.lcd.GraphicsLCD
 
WHITE - Static variable in interface lejos.hardware.sensor.SensorConstants
 
WHITE - Static variable in class lejos.robotics.Color
 
width - Variable in class lejos.hardware.lcd.Font
 
width - Variable in class lejos.robotics.geometry.Rectangle2D.Double
The width of the rectangle
width - Variable in class lejos.robotics.geometry.Rectangle2D.Float
The width of the rectangle
width - Variable in class lejos.robotics.geometry.RectangleInt32
The width of the rectangle
Wifi - Class in lejos.hardware
 
Wifi() - Constructor for class lejos.hardware.Wifi
 
write(int) - Method in class lejos.hardware.device.UART.UARTOutputStream
 
write(byte[], int, int) - Method in class lejos.hardware.device.UART.UARTOutputStream
 
write(byte[], int, int) - Method in class lejos.hardware.device.UART
Write bytes to the device.
write(int) - Method in class lejos.hardware.lcd.LCDOutputStream
 
write(byte[], int, int) - Method in interface lejos.hardware.port.UARTPort
Write bytes to the sensor
write(byte[], int, int) - Method in class lejos.remote.ev3.RemoteRequestUARTPort
 
write(byte[], int, int) - Method in class lejos.remote.ev3.RemoteUARTPort
 
write(byte[], int, int) - Method in class lejos.remote.ev3.RMIRemoteUARTPort
 
write(byte[], int, int) - Method in interface lejos.remote.ev3.RMIUARTPort
Write bytes to the sensor
write(byte[], int) - Method in class lejos.remote.nxt.BTConnection
 
WRITE - Static variable in class lejos.remote.nxt.LCP
 
write(byte[], int) - Method in class lejos.remote.nxt.NXTConnection
 
write(int) - Method in class lejos.remote.nxt.NXTOutputStream
 
WRITE - Static variable in interface lejos.remote.nxt.NXTProtocol
 
write(byte[], int) - Method in class lejos.remote.nxt.SocketConnection
 
writeFile(byte, byte[], int, int) - Method in class lejos.remote.nxt.NXTCommand
Write data to the file

X

x - Variable in class lejos.robotics.geometry.Point2D.Double
The x coordinate of the point
x - Variable in class lejos.robotics.geometry.Point2D.Float
The x coordinate of the point
x - Variable in class lejos.robotics.geometry.Rectangle2D.Double
The x coordinate of the top left corner
x - Variable in class lejos.robotics.geometry.Rectangle2D.Float
The x coordinate of the top left corner
x - Variable in class lejos.robotics.geometry.RectangleInt32
The x coordinate of the top left of the rectangle
x - Variable in class lejos.robotics.pathfinding.Node
The x coordinate of this node.
x1 - Variable in class lejos.robotics.geometry.Line2D.Double
the x coordinate of the start of the line
x1 - Variable in class lejos.robotics.geometry.Line2D.Float
The x coordinate of the start of the line
x2 - Variable in class lejos.robotics.geometry.Line2D.Double
The x coordinate of the end of the line
x2 - Variable in class lejos.robotics.geometry.Line2D.Float
The x coordinate of the end of the line
XYLOPHONE - Static variable in interface lejos.hardware.Sounds
 

Y

y - Variable in class lejos.robotics.geometry.Point2D.Double
The y coordinate of the point
y - Variable in class lejos.robotics.geometry.Point2D.Float
The y coordinate of the point
y - Variable in class lejos.robotics.geometry.Rectangle2D.Double
The y coordinate of the top right corner
y - Variable in class lejos.robotics.geometry.Rectangle2D.Float
The y coordinate of the top right corner
y - Variable in class lejos.robotics.geometry.RectangleInt32
The y coordinate of the top right of the rectangle
y - Variable in class lejos.robotics.pathfinding.Node
The y coordinate of this node.
y1 - Variable in class lejos.robotics.geometry.Line2D.Double
The y coordinate of the sztart of the line
y1 - Variable in class lejos.robotics.geometry.Line2D.Float
The y coordinate of the start of the line
y2 - Variable in class lejos.robotics.geometry.Line2D.Double
The y coordinate of the start of the line
y2 - Variable in class lejos.robotics.geometry.Line2D.Float
The y coordinate of the end of the line
YELLOW - Static variable in interface lejos.hardware.sensor.SensorConstants
 
YELLOW - Static variable in class lejos.robotics.Color
 
YUYVImage - Class in lejos.hardware.video
Class to represent a YUV video image
YUYVImage(byte[], int, int) - Constructor for class lejos.hardware.video.YUYVImage
Create a YUYV image of the requested size using the byte array as the source of pixel information
YUYVImage(int, int) - Constructor for class lejos.hardware.video.YUYVImage
Create a new YUYV image of the specified size

Z

ZERO - Variable in class lejos.robotics.FixedRangeScanner
 
ZERO - Variable in class lejos.robotics.RotatingRangeScanner
 
ZeroFilter - Class in lejos.robotics.filter
Simple filter that adjusts the sample to use a specified zero value
ZeroFilter(SampleProvider, float[]) - Constructor for class lejos.robotics.filter.ZeroFilter
 

_

_blocked - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
set by segmentBlocked() used by findPath()
_blocked - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_blocked - Variable in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
_candidate - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
the set of nodes that are candidates for being in the shortest path, but whose distance from the start node is not yet known
_count - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
 
_direction - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
_distance - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
_estimatedHeading - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
_heading - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
_heading - Variable in class lejos.robotics.navigation.Pose
 
_heading0 - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
_height - Variable in class lejos.utility.TextMenu
number of rows displayed; set by constructor, used by display()
_items - Variable in class lejos.utility.TextMenu
array of items to be displayed ;set by constructor, used by select();
_left - Variable in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Left motor..
_leftDegPerDistance - Variable in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Left motor degrees per unit of travel.
_length - Variable in class lejos.utility.TextMenu
effective length of items array - number of items before null
_location - Variable in class lejos.robotics.navigation.Pose
 
_map - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
The map of the obstacles
_outside - Variable in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
The motor at the outside of the turn.
_p - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_predecessor - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_quit - Variable in class lejos.utility.TextMenu
boolean to cause select to quit
_reached - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
the set of nodes that are candidates for being in the shortest path, and whose distance from the start node is known
_right - Variable in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Right motor.
_rightDegPerDistance - Variable in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
Right motor degrees per unit of travel.
_sourceDistance - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_startTime - Variable in class lejos.utility.TextMenu
start time for select()
_title - Variable in class lejos.utility.TextMenu
optional menu title displayed immediately above the list of items
_topIndex - Variable in class lejos.utility.TextMenu
index of the list item at the top of the list; set by constructor, used by select()
_topRow - Variable in class lejos.utility.TextMenu
location of the top row of the list; set by constructor, used by display()
_traveling - Variable in class lejos.robotics.navigation.CompassPilot
Deprecated.
 
_type - Variable in class lejos.robotics.navigation.DifferentialPilot
Deprecated.
 
A B C D E F G H I J K L M N O P Q R S T U V W X Y Z _