Package com.qualcomm.robotcore.hardware
Class PWMOutputImpl
- java.lang.Object
-
- com.qualcomm.robotcore.hardware.PWMOutputImpl
-
- All Implemented Interfaces:
HardwareDevice
,PWMOutput
- Direct Known Subclasses:
PWMOutputImplEx
public class PWMOutputImpl extends Object implements PWMOutput
Control a single digital port
-
-
Nested Class Summary
-
Nested classes/interfaces inherited from interface com.qualcomm.robotcore.hardware.HardwareDevice
HardwareDevice.Manufacturer
-
-
Field Summary
Fields Modifier and Type Field Description protected PWMOutputController
controller
protected int
port
-
Constructor Summary
Constructors Constructor Description PWMOutputImpl(PWMOutputController controller, int port)
Constructor
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
close()
Closes this deviceString
getConnectionInfo()
Get connection information about this device in a human readable formatString
getDeviceName()
Returns a string suitable for display to the user as to the type of device.HardwareDevice.Manufacturer
getManufacturer()
Returns an indication of the manufacturer of this device.int
getPulseWidthOutputTime()
Get the pulse width output time for this portint
getPulseWidthPeriod()
Get the pulse width outputint
getVersion()
Versionvoid
resetDeviceConfigurationForOpMode()
Resets the device's configuration to that which is expected at the beginning of an OpMode.void
setPulseWidthOutputTime(int time)
Set the pulse width output time for this port.void
setPulseWidthPeriod(int period)
Set the pulse width output period.
-
-
-
Field Detail
-
controller
protected PWMOutputController controller
-
port
protected int port
-
-
Constructor Detail
-
PWMOutputImpl
public PWMOutputImpl(PWMOutputController controller, int port)
Constructor- Parameters:
controller
- Digital port controller this port is attached toport
- 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 interfacePWMOutput
- 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 interfacePWMOutput
-
setPulseWidthPeriod
public void setPulseWidthPeriod(int period)
Set the pulse width output period. Typically set to 20,000 to control servo.- Specified by:
setPulseWidthPeriod
in interfacePWMOutput
- Parameters:
period
- pulse repetition period in microseconds.
-
getPulseWidthPeriod
public int getPulseWidthPeriod()
Get the pulse width output- Specified by:
getPulseWidthPeriod
in interfacePWMOutput
-
getManufacturer
public HardwareDevice.Manufacturer getManufacturer()
Description copied from interface:HardwareDevice
Returns an indication of the manufacturer of this device.- Specified by:
getManufacturer
in interfaceHardwareDevice
- Returns:
- the device's manufacturer
-
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 interfaceHardwareDevice
- 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 interfaceHardwareDevice
- Returns:
- connection info
-
getVersion
public int getVersion()
Description copied from interface:HardwareDevice
Version- Specified by:
getVersion
in interfaceHardwareDevice
- 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 interfaceHardwareDevice
-
close
public void close()
Description copied from interface:HardwareDevice
Closes this device- Specified by:
close
in interfaceHardwareDevice
-
-