public interface DcMotor extends DcMotorSimple
Modifier and Type | Interface and Description |
---|---|
static class |
DcMotor.RunMode
The run mode of a motor
DcMotor.RunMode controls how the motor interprets the
it's parameter settings passed through power- and encoder-related methods. |
static class |
DcMotor.ZeroPowerBehavior
ZeroPowerBehavior provides an indication as to a motor's behavior when a power level of zero
is applied.
|
DcMotorSimple.Direction
HardwareDevice.Manufacturer
Modifier and Type | Method and Description |
---|---|
DcMotorController |
getController()
Returns the underlying motor controller on which this motor is situated.
|
int |
getCurrentPosition()
Returns the current reading of the encoder for this motor.
|
DcMotor.RunMode |
getMode()
Returns the current run mode for this motor
|
MotorConfigurationType |
getMotorType()
Returns the assigned type for this motor.
|
int |
getPortNumber()
Returns the port number on the underlying motor controller on which this motor is situated.
|
boolean |
getPowerFloat()
Returns whether the motor is currently in a float power level.
|
int |
getTargetPosition()
Returns the current target encoder position for this motor.
|
DcMotor.ZeroPowerBehavior |
getZeroPowerBehavior()
Returns the current behavior of the motor were a power level of zero to be applied.
|
boolean |
isBusy()
Returns true if the motor is currently advancing or retreating to a target position.
|
void |
setMode(DcMotor.RunMode mode)
Sets the current run mode for this motor
|
void |
setMotorType(MotorConfigurationType motorType)
Sets the assigned type of this motor.
|
void |
setPowerFloat()
Deprecated.
This method is deprecated in favor of direct use of
setZeroPowerBehavior() and
setPower() . |
void |
setTargetPosition(int position)
Sets the desired encoder target position to which the motor should advance or retreat
and then actively hold thereat.
|
void |
setZeroPowerBehavior(DcMotor.ZeroPowerBehavior zeroPowerBehavior)
Sets the behavior of the motor when a power level of zero is applied.
|
getDirection, getPower, setDirection, setPower
close, getConnectionInfo, getDeviceName, getManufacturer, getVersion, resetDeviceConfigurationForOpMode
MotorConfigurationType getMotorType()
MotorConfigurationType#getUnspecifiedMotorType()
will be returned.
Note that the motor type for a given motor is initially assigned in the robot
configuration user interface, though it may subsequently be modified using methods herein.void setMotorType(MotorConfigurationType motorType)
motorType
- the new assigned type for this motorgetMotorType()
DcMotorController getController()
getPortNumber()
int getPortNumber()
getController()
void setZeroPowerBehavior(DcMotor.ZeroPowerBehavior zeroPowerBehavior)
zeroPowerBehavior
- the new behavior of the motor when a power level of zero is applied.DcMotor.ZeroPowerBehavior
,
DcMotorSimple.setPower(double)
DcMotor.ZeroPowerBehavior getZeroPowerBehavior()
@Deprecated void setPowerFloat()
setZeroPowerBehavior()
and
setPower()
.FLOAT
, then
applies zero power to that motor.
Note that the change of the zero power behavior to FLOAT
remains in effect even following the return of this method. This is a breaking
change in behavior from previous releases of the SDK. Consider, for example, the
following code sequence:
motor.setZeroPowerBehavior(ZeroPowerBehavior.BRAKE); // method not available in previous releases motor.setPowerFloat(); motor.setPower(0.0);
Starting from this release, this sequence of code will leave the motor floating. Previously, the motor would have been left braked.
boolean getPowerFloat()
setPowerFloat()
void setTargetPosition(int position)
isBusy()
will return true.
Note that adjustment to a target position is only effective when the motor is in
RUN_TO_POSITION
RunMode. Note further that, clearly, the motor must be equipped with an encoder in order
for this mode to function properly.
position
- the desired encoder target positiongetCurrentPosition()
,
setMode(RunMode)
,
DcMotor.RunMode.RUN_TO_POSITION
,
getTargetPosition()
,
isBusy()
int getTargetPosition()
setTargetPosition(int)
boolean isBusy()
setTargetPosition(int)
int getCurrentPosition()
getTargetPosition()
,
DcMotor.RunMode.STOP_AND_RESET_ENCODER
void setMode(DcMotor.RunMode mode)
mode
- the new current run mode for this motorDcMotor.RunMode
,
getMode()
DcMotor.RunMode getMode()
DcMotor.RunMode
,
setMode(RunMode)