public class DcMotorImplEx extends DcMotorImpl implements DcMotorEx
DcMotor.RunMode, DcMotor.ZeroPowerBehavior
DcMotorSimple.Direction
HardwareDevice.Manufacturer
controller, direction, motorType, portNumber
Constructor and Description |
---|
DcMotorImplEx(DcMotorController controller,
int portNumber) |
DcMotorImplEx(DcMotorController controller,
int portNumber,
DcMotorSimple.Direction direction) |
DcMotorImplEx(DcMotorController controller,
int portNumber,
DcMotorSimple.Direction direction,
MotorConfigurationType motorType) |
Modifier and Type | Method and Description |
---|---|
protected double |
adjustAngularRate(double angularRate) |
PIDCoefficients |
getPIDCoefficients(DcMotor.RunMode mode)
Returns the PID control coefficients used when running in the indicated mode
on this motor.
|
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
|
protected void |
internalSetTargetPosition(int position) |
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)
Sets the PID control coefficients for one of the PID modes of this motor.
|
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. |
adjustPosition, adjustPower, close, getConnectionInfo, getController, getCurrentPosition, getDeviceName, getDirection, getManufacturer, getMode, getMotorType, getOperationalDirection, getPortNumber, getPower, getPowerFloat, getTargetPosition, getVersion, getZeroPowerBehavior, internalSetMode, internalSetPower, isBusy, resetDeviceConfigurationForOpMode, setDirection, setMode, setMotorType, setPower, setPowerFloat, setTargetPosition, setZeroPowerBehavior
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
getController, getCurrentPosition, getMode, getMotorType, getPortNumber, getPowerFloat, getTargetPosition, getZeroPowerBehavior, isBusy, setMode, setMotorType, setPowerFloat, setTargetPosition, setZeroPowerBehavior
getDirection, getPower, setDirection, setPower
close, getConnectionInfo, getDeviceName, getManufacturer, getVersion, resetDeviceConfigurationForOpMode
public DcMotorImplEx(DcMotorController controller, int portNumber)
public DcMotorImplEx(DcMotorController controller, int portNumber, DcMotorSimple.Direction direction)
public DcMotorImplEx(DcMotorController controller, int portNumber, DcMotorSimple.Direction direction, MotorConfigurationType motorType)
public void setMotorEnable()
DcMotorEx
setMotorEnable
in interface DcMotorEx
DcMotorEx.setMotorDisable()
,
DcMotorEx.isMotorEnabled()
public void setMotorDisable()
DcMotorEx
setMotorDisable
in interface DcMotorEx
DcMotorEx.setMotorEnable()
,
DcMotorEx.isMotorEnabled()
public boolean isMotorEnabled()
DcMotorEx
isMotorEnabled
in interface DcMotorEx
DcMotorEx.setMotorEnable()
,
DcMotorEx.setMotorDisable()
public void setVelocity(double angularRate)
DcMotorEx
setVelocity
in interface DcMotorEx
angularRate
- the desired ticks per secondpublic void setVelocity(double angularRate, AngleUnit unit)
DcMotorEx
setVelocity
in interface DcMotorEx
angularRate
- the desired angular rate, in units per secondunit
- the units in which angularRate is expressedDcMotorEx.getVelocity(AngleUnit)
public double getVelocity()
DcMotorEx
getVelocity
in interface DcMotorEx
public double getVelocity(AngleUnit unit)
DcMotorEx
getVelocity
in interface DcMotorEx
unit
- the units in which the angular rate is desiredDcMotorEx.setVelocity(double, AngleUnit)
protected double adjustAngularRate(double angularRate)
public void setPIDCoefficients(DcMotor.RunMode mode, PIDCoefficients pidCoefficients)
DcMotorEx
setPIDCoefficients
in interface DcMotorEx
mode
- 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)
public void setPIDFCoefficients(DcMotor.RunMode mode, PIDFCoefficients pidfCoefficients)
DcMotorEx
DcMotorEx.setPIDFCoefficients(com.qualcomm.robotcore.hardware.DcMotor.RunMode, com.qualcomm.robotcore.hardware.PIDFCoefficients)
is a superset enhancement to DcMotorEx.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.setPIDFCoefficients
in interface DcMotorEx
DcMotorEx.setVelocityPIDFCoefficients(double, double, double, double)
,
DcMotorEx.setPositionPIDFCoefficients(double)
,
#getPIDFCoefficients(RunMode)
public void setVelocityPIDFCoefficients(double p, double i, double d, double f)
DcMotorEx
DcMotor.RunMode.RUN_USING_ENCODER
mode. MotorControlAlgorithm.PIDF
is used.setVelocityPIDFCoefficients
in interface DcMotorEx
#setPIDFCoefficients(RunMode, PIDFCoefficients)
public void setPositionPIDFCoefficients(double p)
DcMotorEx
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.setPositionPIDFCoefficients
in interface DcMotorEx
DcMotorEx.setVelocityPIDFCoefficients(double, double, double, double)
,
#setPIDFCoefficients(RunMode, PIDFCoefficients)
public PIDCoefficients getPIDCoefficients(DcMotor.RunMode mode)
DcMotorEx
getPIDCoefficients
in interface DcMotorEx
mode
- either RunMode#RUN_USING_ENCODER
or RunMode#RUN_TO_POSITION
public PIDFCoefficients getPIDFCoefficients(DcMotor.RunMode mode)
DcMotorEx
getPIDFCoefficients
in interface DcMotorEx
mode
- either RunMode#RUN_USING_ENCODER
or RunMode#RUN_TO_POSITION
#setPIDFCoefficients(RunMode, PIDFCoefficients)
public int getTargetPositionTolerance()
DcMotorEx
getTargetPositionTolerance
in interface DcMotorEx
public void setTargetPositionTolerance(int tolerance)
DcMotorEx
setTargetPositionTolerance
in interface DcMotorEx
tolerance
- the desired tolerance, in encoder ticksDcMotor.setTargetPosition(int)
protected void internalSetTargetPosition(int position)
internalSetTargetPosition
in class DcMotorImpl