lejos.nxt
Class SensorPort

java.lang.Object
  extended by lejos.nxt.SensorPort
All Implemented Interfaces:
ADSensorPort, BasicSensorPort, I2CPort, LegacySensorPort, ListenerCaller, SensorConstants

public class SensorPort
extends Object
implements LegacySensorPort, I2CPort, ListenerCaller

Abstraction for a NXT input port.


Nested Class Summary
protected  class SensorPort.ColorSensorReader
          Lego Color Sensor driver.
protected  class SensorPort.SensorReader
          The SensorReader class provides a type dependent way to obtain data from a sensor.
protected  class SensorPort.StandardReader
           
 
Field Summary
static int NUMBER_OF_PORTS
          The number of ports available.
static SensorPort[] PORTS
          Deprecated. use getInstance(int) instead.
static int POWER_9V
          Power types.
static int POWER_RCX9V
          Power types.
static int POWER_STD
          Power types.
static SensorPort S1
          Port labeled 1 on NXT.
static SensorPort S2
          Port labeled 2 on NXT.
static SensorPort S3
          Port labeled 3 on NXT.
static SensorPort S4
          Port labeled 4 on NXT.
static int SP_ANA
          Sensor port analogue input (pin 1 on connector)
static int SP_DIGI0
          Sensor port digital I/O 0 (pin 5 on connector)
static int SP_DIGI1
          Sensor port digital I/O 1 (pin 6 on connector)
static int SP_MODE_ADC
          Sensor port pin mode.
static int SP_MODE_INPUT
          Sensor port pin mode.
static int SP_MODE_OFF
          Sensor port pin mode.
static int SP_MODE_OUTPUT
          Sensor port pin mode.
 
Fields inherited from interface lejos.nxt.SensorConstants
BLACK, BLANK_INDEX, BLUE, BLUE_INDEX, GREEN, GREEN_INDEX, MAX_AD_RAW, MAX_TYPE, MIN_TYPE, MODE_ANGLESTEP, MODE_BOOLEAN, MODE_CELSIUS, MODE_FARENHEIT, MODE_PCTFULLSCALE, MODE_PERIODCOUNTER, MODE_RAW, MODE_TRANSITIONCNT, RED, RED_INDEX, TYPE_ANGLE, TYPE_COLORBLUE, TYPE_COLORFULL, TYPE_COLORGREEN, TYPE_COLORNONE, TYPE_COLORRED, TYPE_CUSTOM, TYPE_HISPEED, TYPE_LIGHT_ACTIVE, TYPE_LIGHT_INACTIVE, TYPE_LOWSPEED, TYPE_LOWSPEED_9V, TYPE_NO_SENSOR, TYPE_REFLECTION, TYPE_SOUND_DB, TYPE_SOUND_DBA, TYPE_SWITCH, TYPE_TEMPERATURE, WHITE, YELLOW
 
Fields inherited from interface lejos.nxt.I2CPort
ALWAYS_ACTIVE, ERR_ABORT, ERR_BUS_BUSY, ERR_BUSY, ERR_FAULT, ERR_INVALID_LENGTH, ERR_INVALID_PORT, HIGH_SPEED, LEGO_MODE, MAX_IO, NO_RELEASE, STANDARD_MODE
 
Method Summary
 void activate()
          Activates an RCX sensor.
 void addSensorPortListener(SensorPortListener aListener)
          Adds a port listener.
 int callListeners()
          Call Port Listeners.
 void enableColorSensor()
          Enable the use of the Color Light Sensor on this port.
 int getId()
          Return the ID of the port.
static SensorPort getInstance(int id)
          Return the SensorPort with the given Id.
 int getMode()
          Returns mode compatible with Lego firmware.
 int getSensorPin(int pin)
          Read the current state of a sensor port pin
 int getType()
          Returns type compatible with Lego firmware.
 int i2cComplete(byte[] buffer, int offset, int numBytes)
          Complete an I2C operation and transfer any read bytes
 void i2cDisable()
          Low-level method to disable I2C on the port.
 void i2cEnable(int mode)
          Low-level method to enable I2C on the port.
 int i2cStart(int address, byte[] writeBuffer, int writeOffset, int writeLen, int readLen)
          Low-level method to start an I2C transaction.
 int i2cStatus()
          Low-level method to test if I2C connection is busy.
 int i2cTransaction(int deviceAddress, byte[] writeBuf, int writeOffset, int writeLen, byte[] readBuf, int readOffset, int readLen)
          High level i2c interface.
 void i2cWaitIOComplete()
          Wait for the current IO operation on the i2c port to complete.
 void passivate()
          Passivates an RCX sensor.
 boolean readBooleanValue()
          Reads the boolean value of the sensor.
 int readRawValue()
          Reads the raw value of the sensor.
 int readRawValues(int[] values)
          Return a variable number of raw sensor values
 int readSensorPin(int pin)
          Read the current ADC value from a sensor port pin
 int readValue()
          Returns value compatible with Lego firmware.
 int readValues(int[] values)
          Return a variable number of sensor values
 void reset()
          Reset this port and attempt to reset any attached device.
 void setListenerTolerance(int tolerance)
          Set the tolerance used when triggering a listener event.
 void setMode(int mode)
          Sets mode compatible with Lego firmware.
 void setPowerType(int type)
          Low-level method to set the input power setting for a sensor.
 void setSensorPin(int pin, int val)
          Set the output state of a sensor pin
 void setSensorPinMode(int pin, int mode)
          Low level method to set the operating mode for a sensor pin.
 void setType(int newType)
          Sets type compatible with Lego firmware.
 void setTypeAndMode(int type, int mode)
          Sets type and mode compatible with Lego firmware.
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Field Detail

POWER_STD

public static final int POWER_STD
Power types. 5V standard.

See Also:
Constant Field Values

POWER_RCX9V

public static final int POWER_RCX9V
Power types. 9V pulsed as per RCX.

See Also:
Constant Field Values

POWER_9V

public static final int POWER_9V
Power types. 9V

See Also:
Constant Field Values

SP_DIGI0

public static final int SP_DIGI0
Sensor port digital I/O 0 (pin 5 on connector)

See Also:
Constant Field Values

SP_DIGI1

public static final int SP_DIGI1
Sensor port digital I/O 1 (pin 6 on connector)

See Also:
Constant Field Values

SP_ANA

public static final int SP_ANA
Sensor port analogue input (pin 1 on connector)

See Also:
Constant Field Values

SP_MODE_OFF

public static final int SP_MODE_OFF
Sensor port pin mode. Pin is disabled

See Also:
Constant Field Values

SP_MODE_INPUT

public static final int SP_MODE_INPUT
Sensor port pin mode. Pin is digital input

See Also:
Constant Field Values

SP_MODE_OUTPUT

public static final int SP_MODE_OUTPUT
Sensor port pin mode. Pin is digital output

See Also:
Constant Field Values

SP_MODE_ADC

public static final int SP_MODE_ADC
Sensor port pin mode. Pin is analogue input

See Also:
Constant Field Values

NUMBER_OF_PORTS

public static final int NUMBER_OF_PORTS
The number of ports available.

See Also:
Constant Field Values

S1

public static final SensorPort S1
Port labeled 1 on NXT.


S2

public static final SensorPort S2
Port labeled 2 on NXT.


S3

public static final SensorPort S3
Port labeled 3 on NXT.


S4

public static final SensorPort S4
Port labeled 4 on NXT.


PORTS

@Deprecated
public static final SensorPort[] PORTS
Deprecated. use getInstance(int) instead.
Array containing all three ports [0..3].

Method Detail

getInstance

public static SensorPort getInstance(int id)
Return the SensorPort with the given Id.

Parameters:
id - the Id, between 0 and NUMBER_OF_PORTS-1.
Returns:
the SensorPort object

enableColorSensor

public void enableColorSensor()
Enable the use of the Color Light Sensor on this port. The code for this sensor is relatively large, so it is not presnt by default. Calling this function will enable this code. NOTE: Calling this function will reset the port. If you are using higher level interfaces (like the ColorSensor class, then this call will be made automatically.).


reset

public void reset()
Reset this port and attempt to reset any attached device.


getId

public final int getId()
Return the ID of the port. One of 0, 1, 2 or 3.

Returns:
The Id of this sensor

addSensorPortListener

public void addSensorPortListener(SensorPortListener aListener)
Adds a port listener.

NOTE 1: You can add at most 8 listeners.
NOTE 2: Synchronizing inside listener methods could result in a deadlock.

Parameters:
aListener - Listener for call backs
See Also:
SensorPortListener

setListenerTolerance

public void setListenerTolerance(int tolerance)
Set the tolerance used when triggering a listener event. The event will only trigger when the new value is different from the old value by +/- this amount.

Parameters:
tolerance -

activate

public final void activate()
Activates an RCX sensor. This method should be called if you want to get accurate values from an RCX sensor. In the case of RCX light sensors, you should see the LED go on when you call this method.

Specified by:
activate in interface LegacySensorPort

passivate

public final void passivate()
Passivates an RCX sensor.

Specified by:
passivate in interface LegacySensorPort

getMode

public int getMode()
Returns mode compatible with Lego firmware.

Specified by:
getMode in interface BasicSensorPort
Returns:
the current mode

getType

public int getType()
Returns type compatible with Lego firmware.

Specified by:
getType in interface BasicSensorPort
Returns:
The type of the sensor

setTypeAndMode

public void setTypeAndMode(int type,
                           int mode)
Sets type and mode compatible with Lego firmware.

Specified by:
setTypeAndMode in interface BasicSensorPort
Parameters:
type - the sensor type
mode - the sensor mode

setType

public void setType(int newType)
Sets type compatible with Lego firmware.

Specified by:
setType in interface BasicSensorPort
Parameters:
newType - the sensor type

setMode

public void setMode(int mode)
Sets mode compatible with Lego firmware.

Specified by:
setMode in interface BasicSensorPort
Parameters:
mode - the mode to set.

readRawValue

public final int readRawValue()
Reads the raw value of the sensor.

Specified by:
readRawValue in interface ADSensorPort
Returns:
the raw sensor value

readValue

public int readValue()
Returns value compatible with Lego firmware.

Specified by:
readValue in interface ADSensorPort
Returns:
the computed value

readValues

public int readValues(int[] values)
Return a variable number of sensor values

Parameters:
values - An array in which to return the sensor values.
Returns:
The number of values returned.

readRawValues

public int readRawValues(int[] values)
Return a variable number of raw sensor values

Parameters:
values - An array in which to return the sensor values.
Returns:
The number of values returned.

readBooleanValue

public final boolean readBooleanValue()
Reads the boolean value of the sensor.

Specified by:
readBooleanValue in interface ADSensorPort
Returns:
the boolean state of the sensor

setPowerType

public void setPowerType(int type)
Low-level method to set the input power setting for a sensor. Values are: 0 - no power, 1 RCX active power, 2 power always on.

Parameters:
type - Power type to use

callListeners

public int callListeners()
Call Port Listeners. Used by ListenerThread.

Specified by:
callListeners in interface ListenerCaller
Returns:
New event filter mask.

i2cEnable

public void i2cEnable(int mode)
Low-level method to enable I2C on the port. Note because there can be multiple i2c sensors attached to a single port, only the first enable will set the operating mode.

Specified by:
i2cEnable in interface I2CPort
Parameters:
mode - The operating mode for the device

i2cDisable

public void i2cDisable()
Low-level method to disable I2C on the port. Note if multiple i2c sensors are sharing the same port the port will not be disabled until all of the associated sensors have disabled the port.

Specified by:
i2cDisable in interface I2CPort

i2cWaitIOComplete

public void i2cWaitIOComplete()
Wait for the current IO operation on the i2c port to complete.


i2cStatus

public int i2cStatus()
Low-level method to test if I2C connection is busy.

Specified by:
i2cStatus in interface I2CPort
Returns:
0 if ready -1: Invalid device -2: Device busy -3: Device fault -4: Buffer size error. -5: Bus is busy

i2cStart

public int i2cStart(int address,
                    byte[] writeBuffer,
                    int writeOffset,
                    int writeLen,
                    int readLen)
Low-level method to start an I2C transaction. Any data that is read is obtained via a call to i2cComplete.

Parameters:
address - Address of the device
writeBuffer - Buffer containing bytes to write
writeOffset - Offset into writeBuffer
writeLen - number of bytes to write
readLen - number of bytes to read
Returns:
< 0 error

i2cComplete

public int i2cComplete(byte[] buffer,
                       int offset,
                       int numBytes)
Complete an I2C operation and transfer any read bytes

Parameters:
buffer - Buffer for read data
offset - offset into the buffer
numBytes - Number of bytes to read
Returns:
< 0 error otherwise number of bytes read.

i2cTransaction

public int i2cTransaction(int deviceAddress,
                          byte[] writeBuf,
                          int writeOffset,
                          int writeLen,
                          byte[] readBuf,
                          int readOffset,
                          int readLen)
High level i2c interface. Perform a complete i2c transaction and return the results. Writes the specified data to the device and then reads the requested bytes from it.

Specified by:
i2cTransaction in interface I2CPort
Parameters:
deviceAddress - The I2C device address.
writeBuf - The buffer containing data to be written to the device.
writeOffset - The offset of the data within the write buffer
writeLen - The number of bytes to write.
readBuf - The buffer to use for the transaction results
readOffset - Location to write the results to
readLen - The length of the read
Returns:
< 0 error otherwise the number of bytes read

setSensorPinMode

public void setSensorPinMode(int pin,
                             int mode)
Low level method to set the operating mode for a sensor pin.

Parameters:
pin - The pin id
mode - The new mode

setSensorPin

public void setSensorPin(int pin,
                         int val)
Set the output state of a sensor pin

Parameters:
pin - The pin id
val - The new output value (0/1)

getSensorPin

public int getSensorPin(int pin)
Read the current state of a sensor port pin

Parameters:
pin - The pin id.
Returns:
The current pin state (0/1)

readSensorPin

public int readSensorPin(int pin)
Read the current ADC value from a sensor port pin

Parameters:
pin - The id of the pin to read (SP_DIGI1/SP_ANA)
Returns:
The return from the ADC