|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object lejos.nxt.SensorPort
public class SensorPort
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 way of performing type dependent way to obtain data froma sensor. |
protected class |
SensorPort.StandardReader
|
Field Summary | |
---|---|
static int |
DIGI_0_ON
|
static int |
DIGI_1_ON
|
static int |
DIGI_OFF
|
static int |
DIGI_UNUSED
|
static SensorPort[] |
PORTS
Array containing all three ports [0..3]. |
static int |
POWER_9V
|
static int |
POWER_RCX9V
|
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
|
static int |
SP_DIGI0
|
static int |
SP_DIGI1
|
static int |
SP_MODE_ADC
|
static int |
SP_MODE_INPUT
|
static int |
SP_MODE_OFF
|
static int |
SP_MODE_OUTPUT
|
Fields inherited from interface lejos.nxt.I2CPort |
---|
ALWAYS_ACTIVE, LEGO_MODE, NO_RELEASE, STANDARD_MODE |
Constructor Summary | |
---|---|
protected |
SensorPort(int aId)
|
Method Summary | |
---|---|
void |
activate()
Activates an RCX sensor. |
void |
addSensorPortListener(SensorPortListener aListener)
Adds a port listener. |
void |
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. |
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 |
i2cBusy()
Low-level method to test if I2C connection is busy. |
static int |
i2cBusyById(int aPortId)
Low-level method to test if I2C connection is busy. |
int |
i2cComplete(byte[] buffer,
int numBytes)
Complete an I2C operation and transfer any read bytes |
static int |
i2cCompleteById(int aPortId,
byte[] buffer,
int numBytes)
Complete and I2C operation and retrieve any data read. |
void |
i2cDisable()
Low-level method to disable I2C on the port. |
static void |
i2cDisableById(int aPortId)
Low-level method to disable I2C on the port. |
void |
i2cEnable(int mode)
Low-level method to enable I2C on the port. |
static void |
i2cEnableById(int aPortId,
int mode)
Low-level method to enable I2C on the port. |
int |
i2cStart(int address,
int internalAddress,
int numInternalBytes,
byte[] buffer,
int numBytes,
int transferType)
Low-level method to start an I2C transaction. |
static int |
i2cStartById(int aPortId,
int address,
int internalAddress,
int numInternalBytes,
byte[] buffer,
int numBytes,
int transferType)
Low-level method to start an I2C transaction. |
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 |
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 |
---|
public static final int POWER_STD
public static final int POWER_RCX9V
public static final int POWER_9V
public static final int SP_DIGI0
public static final int SP_DIGI1
public static final int SP_ANA
public static final int SP_MODE_OFF
public static final int SP_MODE_INPUT
public static final int SP_MODE_OUTPUT
public static final int SP_MODE_ADC
public static final int DIGI_UNUSED
public static final int DIGI_OFF
public static final int DIGI_0_ON
public static final int DIGI_1_ON
public static final SensorPort S1
public static final SensorPort S2
public static final SensorPort S3
public static final SensorPort S4
public static final SensorPort[] PORTS
Constructor Detail |
---|
protected SensorPort(int aId)
Method Detail |
---|
public void enableColorSensor()
public void reset()
public final int getId()
public void addSensorPortListener(SensorPortListener aListener)
NOTE 1: You can add at most 8 listeners.
NOTE 2: Synchronizing inside listener methods could result
in a deadlock.
aListener
- Listener for call backsSensorPortListener
public final void activate()
activate
in interface LegacySensorPort
public final void passivate()
passivate
in interface LegacySensorPort
public int getMode()
getMode
in interface BasicSensorPort
public int getType()
getType
in interface BasicSensorPort
public void setTypeAndMode(int type, int mode)
setTypeAndMode
in interface BasicSensorPort
type
- the sensor typemode
- the sensor modepublic void setType(int newType)
setType
in interface BasicSensorPort
newType
- the sensor typepublic void setMode(int mode)
setMode
in interface BasicSensorPort
mode
- the mode to set.public final int readRawValue()
readRawValue
in interface ADSensorPort
public int readValue()
readValue
in interface ADSensorPort
public int readValues(int[] values)
values
- An array in which to return the sensor values.
public int readRawValues(int[] values)
values
- An array in which to return the sensor values.
public final boolean readBooleanValue()
readBooleanValue
in interface ADSensorPort
public void setPowerType(int type)
type
- Power type to usepublic void callListeners()
callListeners
in interface ListenerCaller
public static void i2cEnableById(int aPortId, int mode)
aPortId
- The port number for this devicemode
- I/O mode to usepublic static void i2cDisableById(int aPortId)
aPortId
- The port number for this devicepublic static int i2cBusyById(int aPortId)
aPortId
- The port number for this device
public static int i2cStartById(int aPortId, int address, int internalAddress, int numInternalBytes, byte[] buffer, int numBytes, int transferType)
aPortId
- The port number for this deviceaddress
- The I2C address of the deviceinternalAddress
- The internal address to use for this operationnumInternalBytes
- The number of bytes in the internal addressbuffer
- The buffer for write operationsnumBytes
- Number of bytes to write or readtransferType
- 1==write 0==read
public static int i2cCompleteById(int aPortId, byte[] buffer, int numBytes)
aPortId
- The Port number for the devicebuffer
- The buffer to be used for read operationsnumBytes
- Number of bytes to read
public void i2cEnable(int mode)
i2cEnable
in interface I2CPort
mode
- The operating mode for the devicepublic void i2cDisable()
i2cDisable
in interface I2CPort
public int i2cBusy()
i2cBusy
in interface I2CPort
public int i2cStart(int address, int internalAddress, int numInternalBytes, byte[] buffer, int numBytes, int transferType)
i2cStart
in interface I2CPort
address
- Address of the deviceinternalAddress
- Internal register address for this operationnumInternalBytes
- Size of the internal addressbuffer
- Buffer for write operationsnumBytes
- Number of bytes to read/writetransferType
- 1==write 0 ==read
public int i2cComplete(byte[] buffer, int numBytes)
i2cComplete
in interface I2CPort
buffer
- Buffer for read datanumBytes
- Number of bytes to read
public void setSensorPinMode(int pin, int mode)
pin
- The pin idmode
- The new modepublic void setSensorPin(int pin, int val)
pin
- The pin idval
- The new output value (0/1)public int getSensorPin(int pin)
pin
- The pin id.
public int readSensorPin(int pin)
pin
- The id of the pin to read (SP_DIGI1/SP_ANA)
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |