public interface DcMotorEx extends DcMotor
PwmControl
DcMotor.RunMode, DcMotor.ZeroPowerBehavior
DcMotorSimple.Direction
HardwareDevice.Manufacturer
Modifier and Type | Method and Description |
---|---|
PIDCoefficients |
getPIDCoefficients(DcMotor.RunMode mode)
Deprecated.
Use
#getPIDFCoefficients(RunMode) instead |
PIDFCoefficients |
getPIDFCoefficients(DcMotor.RunMode mode)
Returns the PIDF control coefficients used when running in the indicated mode
on this motor.
|
int |
getTargetPositionTolerance()
Returns the current target positioning tolerance of this motor
|
double |
getVelocity()
Returns the current velocity of the motor, in ticks per second
|
double |
getVelocity(AngleUnit unit)
Returns the current velocity of the motor, in angular units per second
|
boolean |
isMotorEnabled()
Returns whether this motor is energized
|
void |
setMotorDisable()
Individually de-energizes this particular motor
|
void |
setMotorEnable()
Individually energizes this particular motor
|
void |
setPIDCoefficients(DcMotor.RunMode mode,
PIDCoefficients pidCoefficients)
Deprecated.
Use
#setPIDFCoefficients(RunMode, PIDFCoefficients) instead |
void |
setPIDFCoefficients(DcMotor.RunMode mode,
PIDFCoefficients pidfCoefficients)
|
void |
setPositionPIDFCoefficients(double p)
A shorthand for setting the PIDF coefficients for the
DcMotor.RunMode.RUN_TO_POSITION
mode. |
void |
setTargetPositionTolerance(int tolerance)
Sets the target positioning tolerance of this motor
|
void |
setVelocity(double angularRate)
Sets the velocity of the motor
|
void |
setVelocity(double angularRate,
AngleUnit unit)
Sets the velocity of the motor
|
void |
setVelocityPIDFCoefficients(double p,
double i,
double d,
double f)
A shorthand for setting the PIDF coefficients for the
DcMotor.RunMode.RUN_USING_ENCODER
mode. |
getController, getCurrentPosition, getMode, getMotorType, getPortNumber, getPowerFloat, getTargetPosition, getZeroPowerBehavior, isBusy, setMode, setMotorType, setPowerFloat, setTargetPosition, setZeroPowerBehavior
getDirection, getPower, setDirection, setPower
close, getConnectionInfo, getDeviceName, getManufacturer, getVersion, resetDeviceConfigurationForOpMode
void setMotorEnable()
setMotorDisable()
,
isMotorEnabled()
void setMotorDisable()
setMotorEnable()
,
isMotorEnabled()
boolean isMotorEnabled()
setMotorEnable()
,
setMotorDisable()
void setVelocity(double angularRate)
angularRate
- the desired ticks per secondvoid setVelocity(double angularRate, AngleUnit unit)
angularRate
- the desired angular rate, in units per secondunit
- the units in which angularRate is expressedgetVelocity(AngleUnit)
double getVelocity()
double getVelocity(AngleUnit unit)
unit
- the units in which the angular rate is desiredsetVelocity(double, AngleUnit)
@Deprecated void setPIDCoefficients(DcMotor.RunMode mode, PIDCoefficients pidCoefficients)
#setPIDFCoefficients(RunMode, PIDFCoefficients)
insteadmode
- either RunMode#RUN_USING_ENCODER
or RunMode#RUN_TO_POSITION
pidCoefficients
- the new coefficients to use when in that mode on this motor#getPIDCoefficients(RunMode)
void setPIDFCoefficients(DcMotor.RunMode mode, PIDFCoefficients pidfCoefficients) throws java.lang.UnsupportedOperationException
setPIDFCoefficients(com.qualcomm.robotcore.hardware.DcMotor.RunMode, com.qualcomm.robotcore.hardware.PIDFCoefficients)
is a superset enhancement to setPIDCoefficients(com.qualcomm.robotcore.hardware.DcMotor.RunMode, com.qualcomm.robotcore.hardware.PIDCoefficients)
. In addition
to the proportional, integral, and derivative coefficients previously supported, a feed-forward
coefficient may also be specified. Further, a selection of motor control algorithms is offered:
the originally-shipped Legacy PID algorithm, and a PIDF algorithm which avails itself of the
feed-forward coefficient. Note that the feed-forward coefficient is not used by the Legacy PID
algorithm; thus, the feed-forward coefficient must be indicated as zero if the Legacy PID
algorithm is used. Also: the internal implementation of these algorithms may be different: it
is not the case that the use of PIDF with the F term as zero necessarily exhibits exactly the
same behavior as the use of the LegacyPID algorithm, though in practice they will be quite close.
Readers are reminded that DcMotor.RunMode.RUN_TO_POSITION
mode makes use of both
the coefficients set for RUN_TO_POSITION and the coefficients set for RUN_WITH_ENCODER,
due to the fact that internally the RUN_TO_POSITION logic calculates an on-the-fly velocity goal
on each control cycle, then (logically) runs the RUN_WITH_ENCODER logic. Because of that double-
layering, only the proportional ('p') coefficient makes logical sense for use in the RUN_TO_POSITION
coefficients.java.lang.UnsupportedOperationException
setVelocityPIDFCoefficients(double, double, double, double)
,
setPositionPIDFCoefficients(double)
,
#getPIDFCoefficients(RunMode)
void setVelocityPIDFCoefficients(double p, double i, double d, double f)
DcMotor.RunMode.RUN_USING_ENCODER
mode. MotorControlAlgorithm.PIDF
is used.#setPIDFCoefficients(RunMode, PIDFCoefficients)
void setPositionPIDFCoefficients(double p)
DcMotor.RunMode.RUN_TO_POSITION
mode. MotorControlAlgorithm.PIDF
is used.
Readers are reminded that DcMotor.RunMode.RUN_TO_POSITION
mode makes use of both
the coefficients set for RUN_TO_POSITION and the coefficients set for RUN_WITH_ENCODER,
due to the fact that internally the RUN_TO_POSITION logic calculates an on-the-fly velocity goal
on each control cycle, then (logically) runs the RUN_WITH_ENCODER logic. Because of that double-
layering, only the proportional ('p') coefficient makes logical sense for use in the RUN_TO_POSITION
coefficients.setVelocityPIDFCoefficients(double, double, double, double)
,
#setPIDFCoefficients(RunMode, PIDFCoefficients)
@Deprecated PIDCoefficients getPIDCoefficients(DcMotor.RunMode mode)
#getPIDFCoefficients(RunMode)
insteadmode
- either RunMode#RUN_USING_ENCODER
or RunMode#RUN_TO_POSITION
PIDFCoefficients getPIDFCoefficients(DcMotor.RunMode mode)
mode
- either RunMode#RUN_USING_ENCODER
or RunMode#RUN_TO_POSITION
#setPIDFCoefficients(RunMode, PIDFCoefficients)
void setTargetPositionTolerance(int tolerance)
tolerance
- the desired tolerance, in encoder ticksDcMotor.setTargetPosition(int)
int getTargetPositionTolerance()