public interface DcMotorController extends HardwareDevice
Different DC motor controllers will implement this interface.
HardwareDevice.Manufacturer
Modifier and Type | Method and Description |
---|---|
int |
getMotorCurrentPosition(int motor)
Get the current motor position
|
DcMotor.RunMode |
getMotorMode(int motor)
Get the current motor mode.
|
double |
getMotorPower(int motor)
Get the current motor power
|
boolean |
getMotorPowerFloat(int motor)
Is motor power set to float?
|
int |
getMotorTargetPosition(int motor)
Get the current motor target position
|
MotorConfigurationType |
getMotorType(int motor)
Retrieves the motor type configured for this motor
|
DcMotor.ZeroPowerBehavior |
getMotorZeroPowerBehavior(int motor)
Returns the current zero power behavior of the motor.
|
boolean |
isBusy(int motor)
Is the motor busy?
|
void |
resetDeviceConfigurationForOpMode(int motor)
Reset the state we hold for the given motor so that it's clean at the start of an opmode
|
void |
setMotorMode(int motor,
DcMotor.RunMode mode)
Set the current motor mode.
|
void |
setMotorPower(int motor,
double power)
Set the current motor power
|
void |
setMotorTargetPosition(int motor,
int position)
Set the motor target position.
|
void |
setMotorType(int motor,
MotorConfigurationType motorType)
Informs the motor controller of the type of a particular motor.
|
void |
setMotorZeroPowerBehavior(int motor,
DcMotor.ZeroPowerBehavior zeroPowerBehavior)
Sets the behavior of the motor when zero power is applied.
|
close, getConnectionInfo, getDeviceName, getManufacturer, getVersion, resetDeviceConfigurationForOpMode
void setMotorType(int motor, MotorConfigurationType motorType)
motor
- port of the motor in questionmotorType
- the motor type.MotorConfigurationType getMotorType(int motor)
motor
- the motor in questionMotorConfigurationType#getUnspecifiedMotorType()
if no type has been configuredvoid setMotorMode(int motor, DcMotor.RunMode mode)
DcMotor.RunMode
motor
- port of motormode
- run modeDcMotor.RunMode getMotorMode(int motor)
motor
- port of motorvoid setMotorPower(int motor, double power)
motor
- port of motorpower
- from -1.0 to 1.0double getMotorPower(int motor)
motor
- port of motorboolean isBusy(int motor)
motor
- port of motorvoid setMotorZeroPowerBehavior(int motor, DcMotor.ZeroPowerBehavior zeroPowerBehavior)
zeroPowerBehavior
- the behavior of the motor when zero power is applied.DcMotor.ZeroPowerBehavior getMotorZeroPowerBehavior(int motor)
boolean getMotorPowerFloat(int motor)
motor
- port of motorvoid setMotorTargetPosition(int motor, int position)
motor
- port of motorposition
- range from Integer.MIN_VALUE to Integer.MAX_VALUEint getMotorTargetPosition(int motor)
motor
- port of motorint getMotorCurrentPosition(int motor)
motor
- port of motorvoid resetDeviceConfigurationForOpMode(int motor)
motor
-