public interface DcMotorControllerEx extends DcMotorController
DcMotorExHardwareDevice.Manufacturer| Modifier and Type | Method and Description |
|---|---|
double |
getMotorCurrent(int motor,
CurrentUnit unit)
Returns the current consumed by the indicated motor.
|
double |
getMotorCurrentAlert(int motor,
CurrentUnit unit)
Returns the current alert for the indicated motor.
|
double |
getMotorVelocity(int motor)
Returns the velocity of the indicated motor in ticks per second.
|
double |
getMotorVelocity(int motor,
AngleUnit unit)
Returns the velocity of the indicated motor.
|
PIDCoefficients |
getPIDCoefficients(int motor,
DcMotor.RunMode mode)
Deprecated.
Use
getPIDFCoefficients(int, DcMotor.RunMode) instead |
PIDFCoefficients |
getPIDFCoefficients(int motor,
DcMotor.RunMode mode)
Returns the coefficients used for PIDF control on the indicated motor when in the indicated mode
|
boolean |
isMotorEnabled(int motor)
Returns whether a particular motor on the controller is energized
|
boolean |
isMotorOverCurrent(int motor)
Returns whether the indicated motor current consumption has exceeded the alert threshold.
|
void |
setMotorCurrentAlert(int motor,
double current,
CurrentUnit unit)
Sets the current alert for the indicated motor
|
void |
setMotorDisable(int motor)
Individually denergizes a particular motor
|
void |
setMotorEnable(int motor)
Individually energizes a particular motor
|
void |
setMotorTargetPosition(int motor,
int position,
int tolerance)
Sets the target position and tolerance for a 'run to position' operation.
|
void |
setMotorVelocity(int motor,
double ticksPerSecond)
Sets the target velocity of the indicated motor.
|
void |
setMotorVelocity(int motor,
double angularRate,
AngleUnit unit)
Sets the target velocity of the indicated motor.
|
void |
setPIDCoefficients(int motor,
DcMotor.RunMode mode,
PIDCoefficients pidCoefficients)
Deprecated.
|
void |
setPIDFCoefficients(int motor,
DcMotor.RunMode mode,
PIDFCoefficients pidfCoefficients)
Sets the coefficients used for PIDF control on the indicated motor when in the indicated mode
|
getMotorCurrentPosition, getMotorMode, getMotorPower, getMotorPowerFloat, getMotorTargetPosition, getMotorType, getMotorZeroPowerBehavior, isBusy, resetDeviceConfigurationForOpMode, setMotorMode, setMotorPower, setMotorTargetPosition, setMotorType, setMotorZeroPowerBehaviorclose, getConnectionInfo, getDeviceName, getManufacturer, getVersion, resetDeviceConfigurationForOpModevoid setMotorEnable(int motor)
motor - the port number of the motor on this controllersetMotorDisable(int),
isMotorEnabled(int)void setMotorDisable(int motor)
motor - the port number of the motor on this controllersetMotorEnable(int),
isMotorEnabled(int)boolean isMotorEnabled(int motor)
motor - the port number of the motor on this controllersetMotorEnable(int),
setMotorDisable(int)void setMotorVelocity(int motor,
double ticksPerSecond)
motor - the port number of the motor on this controllerticksPerSecond - the new target rate for that motor, in ticks per secondvoid setMotorVelocity(int motor,
double angularRate,
AngleUnit unit)
motor - motor whose velocity is to be adjustedangularRate - the new target rate for that motor, in 'unit's per secondunit - the unit inw which angularRate is expressed.DcMotorEx.setVelocity(double, AngleUnit)double getMotorVelocity(int motor)
motor - the motor whose velocity is desireddouble getMotorVelocity(int motor,
AngleUnit unit)
motor - the motor whose velocity is desiredunit - the angular unit in which the velocity is to be expressedDcMotorEx.getVelocity(AngleUnit)@Deprecated
void setPIDCoefficients(int motor,
DcMotor.RunMode mode,
PIDCoefficients pidCoefficients)
setPIDFCoefficients(int, DcMotor.RunMode, PIDFCoefficients) insteadmotor - the motor whose PID coefficients are to be setmode - the mode on that motor whose coefficients are to be setpidCoefficients - the new coefficients to setDcMotorEx.setPIDCoefficients(DcMotor.RunMode, PIDCoefficients),
getPIDCoefficients(int, DcMotor.RunMode)void setPIDFCoefficients(int motor,
DcMotor.RunMode mode,
PIDFCoefficients pidfCoefficients)
throws java.lang.UnsupportedOperationException
motor - the motor whose PIDF coefficients are to be setmode - the mode on that motor whose coefficients are to be setpidfCoefficients - the new coefficients to setjava.lang.UnsupportedOperationExceptionDcMotorEx.setPIDFCoefficients(DcMotor.RunMode, PIDFCoefficients),
getPIDFCoefficients(int, DcMotor.RunMode)@Deprecated PIDCoefficients getPIDCoefficients(int motor, DcMotor.RunMode mode)
getPIDFCoefficients(int, DcMotor.RunMode) insteadmotor - the motor whose PID coefficients are desiredmode - the mode on that motor whose coefficients are to be queriedDcMotorEx.getPIDCoefficients(DcMotor.RunMode),
setPIDCoefficients(int, DcMotor.RunMode, PIDCoefficients)PIDFCoefficients getPIDFCoefficients(int motor, DcMotor.RunMode mode)
motor - the motor whose PIDF coefficients are desiredmode - the mode on that motor whose coefficients are to be queriedDcMotorEx.getPIDCoefficients(DcMotor.RunMode),
setPIDFCoefficients(int, DcMotor.RunMode, PIDFCoefficients)void setMotorTargetPosition(int motor,
int position,
int tolerance)
motor - the motor number to be affectedposition - the desired target position, in encoder tickstolerance - the tolerance of the desired target position, in encoder ticksdouble getMotorCurrent(int motor,
CurrentUnit unit)
motor - motor whose current consumption is desiredunit - current unitsDcMotorEx.getCurrent(CurrentUnit)double getMotorCurrentAlert(int motor,
CurrentUnit unit)
motor - motor whose alert is desiredunit - current unitssetMotorCurrentAlert(int, double, CurrentUnit),
DcMotorEx.setCurrentAlert(double, CurrentUnit),
isMotorOverCurrent(int)void setMotorCurrentAlert(int motor,
double current,
CurrentUnit unit)
motor - motor whose alert is to be setcurrent - current alertunit - current unitsgetMotorCurrentAlert(int, CurrentUnit),
DcMotorEx.getCurrentAlert(CurrentUnit),
isMotorOverCurrent(int)boolean isMotorOverCurrent(int motor)
motor - desired motorDcMotorEx.isOverCurrent(),
getMotorCurrentAlert(int, CurrentUnit),
setMotorCurrentAlert(int, double, CurrentUnit)