Class FtcI2cDeviceSynch

java.lang.Object
com.qualcomm.robotcore.hardware.I2cDeviceSynchDevice<com.qualcomm.robotcore.hardware.I2cDeviceSynch>
ftclib.robotcore.FtcI2cDeviceSynch
All Implemented Interfaces:
com.qualcomm.robotcore.hardware.HardwareDevice, com.qualcomm.robotcore.hardware.usb.RobotArmingStateNotifier.Callback

@I2cDeviceType @DeviceProperties(name="I2C Sync Device", description="I2C Sync Device", xmlTag="I2cSyncDevice") public class FtcI2cDeviceSynch extends com.qualcomm.robotcore.hardware.I2cDeviceSynchDevice<com.qualcomm.robotcore.hardware.I2cDeviceSynch>
This class implements a platform dependent I2C Device that provides synchronous read/write access to the device. For efficiency, it also provides a buffered read mode that uses the FTC I2C ReadWindow interface to read the maximum allowable number of bytes into a buffer. Then it will return data from this buffer FIFO and read the next buffer if necessary.
  • Nested Class Summary

    Nested classes/interfaces inherited from interface com.qualcomm.robotcore.hardware.HardwareDevice

    com.qualcomm.robotcore.hardware.HardwareDevice.Manufacturer
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    private byte[]
     
    private int
     
    private int
     
    private final com.qualcomm.robotcore.hardware.I2cDeviceSynch
     
    private String
     
    private com.qualcomm.robotcore.hardware.HardwareDevice.Manufacturer
     

    Fields inherited from class com.qualcomm.robotcore.hardware.I2cDeviceSynchDevice

    deviceClient, deviceClientIsOwned, isInitialized
  • Constructor Summary

    Constructors
    Constructor
    Description
    FtcI2cDeviceSynch(com.qualcomm.robotcore.hardware.I2cDeviceSynch device)
    Constructor: Creates an instance of the object.
  • Method Summary

    Modifier and Type
    Method
    Description
    protected boolean
    This method is called to initialize the device.
    Returns a string suitable for display to the user as to the type of device.
    com.qualcomm.robotcore.hardware.HardwareDevice.Manufacturer
    This method returns the manufacture of the device.
    boolean
    This method checks if the pixy camera is enabled.
    byte[]
    readData(int len)
    This method reads the specified number of bytes from the device.
    byte[]
    readData(int startReg, int len)
    This method reads the specified number of bytes from the device start at the specified register.
    void
    setBufferedReadWindow(int startReg, int cbReg, com.qualcomm.robotcore.hardware.I2cDeviceSynch.ReadMode readMode, int bufferSize)
    This method sets the read window for reading a number of registers all at once into a data buffer.
    void
    setDeviceInfo(com.qualcomm.robotcore.hardware.HardwareDevice.Manufacturer manufacturer, String deviceName)
    This method sets the device manufacturer and name.
    void
    setEnabled(boolean enabled)
    This method enables/disables the pixy camera.
    void
    setI2cAddress(int i2cAddress, boolean addressIs7Bit)
    This method sets the I2C address of the device.
    This method returns the device name.
    void
    writeData(int startReg, byte[] data, boolean waitForCompletion)
    This method writes the specified number of bytes to the device via theI2cDeviceSynch.

    Methods inherited from class com.qualcomm.robotcore.hardware.I2cDeviceSynchDevice

    close, disengage, engage, getConnectionInfo, getDeviceClient, getVersion, initialize, initializeIfNecessary, onModuleStateChange, registerArmingStateCallback, resetDeviceConfigurationForOpMode

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
  • Field Details

    • device

      private final com.qualcomm.robotcore.hardware.I2cDeviceSynch device
    • manufacturer

      private com.qualcomm.robotcore.hardware.HardwareDevice.Manufacturer manufacturer
    • deviceName

      private String deviceName
    • bufferSize

      private int bufferSize
    • buffer

      private byte[] buffer
    • buffIndex

      private int buffIndex
  • Constructor Details

    • FtcI2cDeviceSynch

      public FtcI2cDeviceSynch(com.qualcomm.robotcore.hardware.I2cDeviceSynch device)
      Constructor: Creates an instance of the object. This is intended to be called by the FTC SDK and the instance will be available by calling hardwareMap.get(FtcI2cDeviceSynch.class, instanceName).
      Parameters:
      device - specifies the synchronous I2C device.
  • Method Details

    • toString

      @NonNull public String toString()
      This method returns the device name.
      Overrides:
      toString in class Object
      Returns:
      device name.
    • isEnabled

      public boolean isEnabled()
      This method checks if the pixy camera is enabled.
      Returns:
      true if pixy camera is enabled, false otherwise.
    • setEnabled

      public void setEnabled(boolean enabled)
      This method enables/disables the pixy camera.
      Parameters:
      enabled - specifies true to enable pixy camera, false to disable.
    • setI2cAddress

      public void setI2cAddress(int i2cAddress, boolean addressIs7Bit)
      This method sets the I2C address of the device.
      Parameters:
      i2cAddress - specifies the I2C address.
      addressIs7Bit - specifies true if it is a 7-bit address, false if it is an 8-bit address.
    • setDeviceInfo

      public void setDeviceInfo(com.qualcomm.robotcore.hardware.HardwareDevice.Manufacturer manufacturer, String deviceName)
      This method sets the device manufacturer and name.
      Parameters:
      manufacturer - specifies device manufacturer.
      deviceName - specifies device name.
    • setBufferedReadWindow

      public void setBufferedReadWindow(int startReg, int cbReg, com.qualcomm.robotcore.hardware.I2cDeviceSynch.ReadMode readMode, int bufferSize)
      This method sets the read window for reading a number of registers all at once into a data buffer. This is primarily setting up for the readBufferedData method. If there is an existing buffer with data in it, this call will blow that away and resets the index.
      Parameters:
      startReg - specifies the start register number of the window.
      cbReg - specifies the number of bytes to be read from the window.
      readMode - specifies the read window mode.
      bufferSize - specifies the buffer size to be used.
    • writeData

      public void writeData(int startReg, byte[] data, boolean waitForCompletion)
      This method writes the specified number of bytes to the device via theI2cDeviceSynch.
      Parameters:
      startReg - specifies the start register to read.
      data - specifies the number of bytes to read from the device.
      waitForCompletion - specifies true to wait for write completion.
    • readData

      public byte[] readData(int startReg, int len)
      This method reads the specified number of bytes from the device start at the specified register.
      Parameters:
      startReg - specifies the start register to read.
      len - specifies the number of bytes to read.
      Returns:
      data read.
    • readData

      public byte[] readData(int len)
      This method reads the specified number of bytes from the device. If a buffer read window is set up, it reads the data from the data buffer else it reads the data from the device directly. The I2cDeviceSynch class implemented a read window that buffers a number of bytes. This method will return the specified bytes from this buffer. If the data in the buffer runs out, it will read in the next buffer. If there is no more data from the device, it will just return the data read so far or if there was none, null is returned.
      Parameters:
      len - specifies the number of bytes to read from the device.
      Returns:
      specified number of the bytes from the device.
    • doInitialize

      protected boolean doInitialize()
      This method is called to initialize the device. There is nothing to do in this case.
      Specified by:
      doInitialize in class com.qualcomm.robotcore.hardware.I2cDeviceSynchDevice<com.qualcomm.robotcore.hardware.I2cDeviceSynch>
      Returns:
      true.
    • getManufacturer

      public com.qualcomm.robotcore.hardware.HardwareDevice.Manufacturer getManufacturer()
      This method returns the manufacture of the device.
      Returns:
      manufacturer.
    • getDeviceName

      public String getDeviceName()
      Returns a string suitable for display to the user as to the type of device. Note that this is a device-type-specific name; it has nothing to do with the name by which a user might have configured the device in a robot configuration.
      Returns:
      device name string.