Class PWMOutputImpl

    • Constructor Detail

      • PWMOutputImpl

        public PWMOutputImpl​(PWMOutputController controller,
                             int port)
        Constructor
        Parameters:
        controller - Digital port controller this port is attached to
        port - port on the digital port controller
    • Method Detail

      • setPulseWidthOutputTime

        public void setPulseWidthOutputTime​(int time)
        Set the pulse width output time for this port. Typically set to a value between 750 and 2,250 to control a servo.
        Specified by:
        setPulseWidthOutputTime in interface PWMOutput
        Parameters:
        time - pulse width for the port in microseconds.
      • getPulseWidthOutputTime

        public int getPulseWidthOutputTime()
        Get the pulse width output time for this port
        Specified by:
        getPulseWidthOutputTime in interface PWMOutput
      • setPulseWidthPeriod

        public void setPulseWidthPeriod​(int period)
        Set the pulse width output period. Typically set to 20,000 to control servo.
        Specified by:
        setPulseWidthPeriod in interface PWMOutput
        Parameters:
        period - pulse repetition period in microseconds.
      • getPulseWidthPeriod

        public int getPulseWidthPeriod()
        Get the pulse width output
        Specified by:
        getPulseWidthPeriod in interface PWMOutput
      • getDeviceName

        public String getDeviceName()
        Description copied from interface: HardwareDevice
        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.
        Specified by:
        getDeviceName in interface HardwareDevice
        Returns:
        device manufacturer and name
      • getConnectionInfo

        public String getConnectionInfo()
        Description copied from interface: HardwareDevice
        Get connection information about this device in a human readable format
        Specified by:
        getConnectionInfo in interface HardwareDevice
        Returns:
        connection info
      • getVersion

        public int getVersion()
        Description copied from interface: HardwareDevice
        Version
        Specified by:
        getVersion in interface HardwareDevice
        Returns:
        get the version of this device
      • resetDeviceConfigurationForOpMode

        public void resetDeviceConfigurationForOpMode()
        Description copied from interface: HardwareDevice
        Resets the device's configuration to that which is expected at the beginning of an OpMode. For example, motors will reset the their direction to 'forward'.
        Specified by:
        resetDeviceConfigurationForOpMode in interface HardwareDevice