public interface I2cDevice extends I2cControllerPortDevice, HardwareDevice
I2cDevice
interface abstracts the engine used to interact on with a specific I2c device
on a port of an I2cController
.I2cDeviceSynch
HardwareDevice.Manufacturer
Modifier and Type | Method and Description |
---|---|
void |
clearI2cPortActionFlag()
Clears the flag that
setI2cPortActionFlag() sets |
void |
copyBufferIntoWriteBuffer(byte[] buffer)
Atomically copies the provided buffer into the user portion of the write cache, beginning
immediately following the four-byte header.
|
void |
deregisterForPortReadyBeginEndCallback()
Unregisters any portIsReady() begin / end notifications object if any is present.
|
void |
deregisterForPortReadyCallback()
Unregisters any callback currently registered.
|
void |
enableI2cReadMode(I2cAddr i2cAddr,
int register,
int count)
Enable read mode for this I2C device.
|
void |
enableI2cWriteMode(I2cAddr i2cAddr,
int register,
int count)
Enable write mode for this I2C device.
|
int |
getCallbackCount()
Returns the number of callbacks ever experienced by this I2cDevice instance, whether or not
they were ever seen by a registered callback.
|
I2cController |
getController()
Deprecated.
Use of
I2cControllerPortDevice.getI2cController() is suggested instead |
byte[] |
getCopyOfReadBuffer()
Atomically returns a copy of that portion of the read-cache which does not include the
initial four-byte header section: that contains the read payload most recently read from
the controller.
|
byte[] |
getCopyOfWriteBuffer()
Atomically returns a copy that portion of the write-cache which does not include the
initial four-byte header section.
|
I2cController.I2cPortReadyCallback |
getI2cPortReadyCallback()
Returns the callback previously registered with
registerForI2cPortReadyCallback(com.qualcomm.robotcore.hardware.I2cController.I2cPortReadyCallback) , or
null if no callback is currently registered. |
byte[] |
getI2cReadCache()
Returns access to the read-cache into which data from the controller is read.
|
java.util.concurrent.locks.Lock |
getI2cReadCacheLock()
Returns access to the lock controlling the read-cache.
|
TimeWindow |
getI2cReadCacheTimeWindow()
Returns the time window object into which time stamps are written when the read cache is updated
|
byte[] |
getI2cWriteCache()
Returns access to the write-cache from which data is written to the controller.
|
java.util.concurrent.locks.Lock |
getI2cWriteCacheLock()
Returns access to the lock controlling the write-cache.
|
int |
getMaxI2cWriteLatency()
Returns the maximum interval, in milliseconds, from when the controller receives an I2c write
transmission over USB to when that write is actually issued to the I2c device.
|
I2cController.I2cPortReadyBeginEndNotifications |
getPortReadyBeginEndCallback()
Returns the object, if any, currently registered for portIsReady() begin / end notifications
|
boolean |
isArmed()
Returns whether, as of this instant, this I2cDevice is alive and operational in
its normally expected mode; that is, whether it is currently in communication
with its underlying hardware or whether it is in some other state
|
boolean |
isI2cPortActionFlagSet()
Deprecated.
this method returns a value that is rarely that which is expected
|
boolean |
isI2cPortInReadMode()
Queries whether or not the controller has reported that it is in read mode.
|
boolean |
isI2cPortInWriteMode()
Queries whether or not the controller has reported that it is in write mode.
|
boolean |
isI2cPortReady()
Returns whether the I2cDevice instance has experienced a callback since the last issuance
of work to the controller.
|
void |
readI2cCacheFromController()
Enqueue a request to the controller to read the range of data from the HW device that
was previously indicated in
enableI2cReadMode(I2cAddr, int, int) and subsequently written
to the controller. |
void |
readI2cCacheFromModule()
Deprecated.
Use of
readI2cCacheFromController() is suggested instead |
void |
registerForI2cPortReadyCallback(I2cController.I2cPortReadyCallback callback)
Registers an object to get
portIsReady()
callbacks at regular intervals from the I2cDevice . |
void |
registerForPortReadyBeginEndCallback(I2cController.I2cPortReadyBeginEndNotifications callback)
Register for notifications as to when
portIsReady()
begin and end. |
void |
setI2cPortActionFlag()
Set the flag in the write cache that indicates that when the write cache is next transferred
to the controller an i2c transaction should take place.
|
void |
writeI2cCacheToController()
Enqueue a request to the controller to write the current contents of the write cache
to the HW device.
|
void |
writeI2cCacheToModule()
Deprecated.
Use of
writeI2cCacheToController() is suggested instead |
void |
writeI2cPortFlagOnlyToController()
Enqueue a request to the controller to reissue the previous i2c transaction to the HW device.
|
void |
writeI2cPortFlagOnlyToModule()
Deprecated.
Use of
writeI2cPortFlagOnlyToController() is suggested instead |
getI2cController, getPort
close, getConnectionInfo, getDeviceName, getManufacturer, getVersion, resetDeviceConfigurationForOpMode
void enableI2cReadMode(I2cAddr i2cAddr, int register, int count)
i2cAddr
- the address of the device on the I2c bus which should be readregister
- I2c register number within the device at which to start readingcount
- number of bytes to readwriteI2cCacheToController()
void enableI2cWriteMode(I2cAddr i2cAddr, int register, int count)
i2cAddr
- the address of the device on the I2c bus which should be writtenregister
- mem address at which to start writingcount
- number of bytes to writewriteI2cCacheToController()
boolean isI2cPortInReadMode()
boolean isI2cPortInWriteMode()
void readI2cCacheFromController()
enableI2cReadMode(I2cAddr, int, int)
and subsequently written
to the controller.void writeI2cCacheToController()
void writeI2cPortFlagOnlyToController()
void setI2cPortActionFlag()
enableI2cReadMode(I2cAddr, int, int)
or
enableI2cWriteMode(I2cAddr, int, int)
has most recently been called.clearI2cPortActionFlag()
@Deprecated boolean isI2cPortActionFlagSet()
I2cDevice
client; it's use generally should be avoided.void clearI2cPortActionFlag()
setI2cPortActionFlag()
setssetI2cPortActionFlag()
byte[] getI2cReadCache()
getI2cReadCache()
need not be repeatedly
called. The lock returned by getI2cReadCacheLock()
must be held whenever the data
in the returned byte array is accessed. Note that the returned byte array contains an initial
header section, four bytes in size, which contains the information manipulated by
enableI2cReadMode(I2cAddr, int, int)
and enableI2cWriteMode(I2cAddr, int, int)
.getI2cReadCacheLock()
,
getCopyOfReadBuffer()
TimeWindow getI2cReadCacheTimeWindow()
getI2cReadCache()
java.util.concurrent.locks.Lock getI2cReadCacheLock()
getI2cReadCache()
is accessed.byte[] getI2cWriteCache()
getI2cWriteCache()
need not be repeatedly
called. The lock returned by getI2cWriteCacheLock()
must be held whenever the data
in the returned byte array is accessed or written. Note that the returned byte array contains
an inital header section, four bytes in size, which contains the information manipulated by
enableI2cReadMode(I2cAddr, int, int)
and enableI2cWriteMode(I2cAddr, int, int)
.getI2cWriteCacheLock()
,
getCopyOfWriteBuffer()
java.util.concurrent.locks.Lock getI2cWriteCacheLock()
getI2cWriteCache()
is accessedbyte[] getCopyOfReadBuffer()
getI2cReadCache()
byte[] getCopyOfWriteBuffer()
getI2cWriteCache()
void copyBufferIntoWriteBuffer(byte[] buffer)
buffer
- the data to copy into the write cachegetI2cWriteCache()
int getMaxI2cWriteLatency()
void registerForI2cPortReadyCallback(I2cController.I2cPortReadyCallback callback)
portIsReady()
callbacks at regular intervals from the I2cDevice
. Only one object may be registered for a callback
with an I2cDevice
at any given time.callback
- getI2cPortReadyCallback()
,
deregisterForPortReadyCallback()
I2cController.I2cPortReadyCallback getI2cPortReadyCallback()
registerForI2cPortReadyCallback(com.qualcomm.robotcore.hardware.I2cController.I2cPortReadyCallback)
, or
null if no callback is currently registered.void deregisterForPortReadyCallback()
int getCallbackCount()
I2cDevice
instanceboolean isI2cPortReady()
portIsReady()
callback and putting your processing logic there. Inside the callback, the port is, by definition, ready.
Alternately, consider using the I2cDeviceSynch
interface instead.I2cDeviceSynch
,
registerForI2cPortReadyCallback(I2cController.I2cPortReadyCallback)
void registerForPortReadyBeginEndCallback(I2cController.I2cPortReadyBeginEndNotifications callback)
portIsReady()
begin and end. Only one object may be registered for such notifications with an I2cDevice at
any given time.callback
- getPortReadyBeginEndCallback()
,
deregisterForPortReadyBeginEndCallback()
I2cController.I2cPortReadyBeginEndNotifications getPortReadyBeginEndCallback()
registerForPortReadyBeginEndCallback(I2cController.I2cPortReadyBeginEndNotifications)
void deregisterForPortReadyBeginEndCallback()
boolean isArmed()
@Deprecated I2cController getController()
I2cControllerPortDevice.getI2cController()
is suggested instead@Deprecated void readI2cCacheFromModule()
readI2cCacheFromController()
is suggested instead@Deprecated void writeI2cCacheToModule()
writeI2cCacheToController()
is suggested instead@Deprecated void writeI2cPortFlagOnlyToModule()
writeI2cPortFlagOnlyToController()
is suggested instead