public static enum DcMotor.RunMode extends java.lang.Enum<DcMotor.RunMode>
DcMotor.RunMode
controls how the motor interprets the
it's parameter settings passed through power- and encoder-related methods.
Some of these modes internally use PID
control to achieve their function, while others do not. Those that do are referred
to as "PID modes".Enum Constant and Description |
---|
RESET_ENCODERS
Deprecated.
Use
STOP_AND_RESET_ENCODER instead |
RUN_TO_POSITION
The motor is to attempt to rotate in whatever direction is necessary to cause the
encoder reading to advance or retreat from its current setting to the setting which
has been provided through the
setTargetPosition() method. |
RUN_USING_ENCODER
The motor is to do its best to run at targeted velocity.
|
RUN_USING_ENCODERS
Deprecated.
Use
RUN_USING_ENCODER instead |
RUN_WITHOUT_ENCODER
The motor is simply to run at whatever velocity is achieved by apply a particular
power level to the motor.
|
RUN_WITHOUT_ENCODERS
Deprecated.
Use
RUN_WITHOUT_ENCODER instead |
STOP_AND_RESET_ENCODER
The motor is to set the current encoder position to zero.
|
Modifier and Type | Method and Description |
---|---|
boolean |
isPIDMode()
Returns whether this RunMode is a PID-controlled mode or not
|
DcMotor.RunMode |
migrate()
Deprecated.
Replace use of old constants with new
|
static DcMotor.RunMode |
valueOf(java.lang.String name)
Returns the enum constant of this type with the specified name.
|
static DcMotor.RunMode[] |
values()
Returns an array containing the constants of this enum type, in
the order they are declared.
|
public static final DcMotor.RunMode RUN_WITHOUT_ENCODER
public static final DcMotor.RunMode RUN_USING_ENCODER
public static final DcMotor.RunMode RUN_TO_POSITION
setTargetPosition()
method.
An encoder must be affixed to this motor in order to use this mode. This is a PID mode.public static final DcMotor.RunMode STOP_AND_RESET_ENCODER
RUN_TO_POSITION
,
the motor is not rotated in order to achieve this; rather, the current rotational
position of the motor is simply reinterpreted as the new zero value. However, as
a side effect of placing a motor in this mode, power is removed from the motor, causing
it to stop, though it is unspecified whether the motor enters brake or float mode.
Further, it should be noted that setting a motor toSTOP_AND_RESET_ENCODER
may or may not be a transient state: motors connected to some motor
controllers will remain in this mode until explicitly transitioned to a different one, while
motors connected to other motor controllers will automatically transition to a different
mode after the reset of the encoder is complete.@Deprecated public static final DcMotor.RunMode RUN_WITHOUT_ENCODERS
RUN_WITHOUT_ENCODER
instead@Deprecated public static final DcMotor.RunMode RUN_USING_ENCODERS
RUN_USING_ENCODER
instead@Deprecated public static final DcMotor.RunMode RESET_ENCODERS
STOP_AND_RESET_ENCODER
insteadpublic static DcMotor.RunMode[] values()
for (DcMotor.RunMode c : DcMotor.RunMode.values()) System.out.println(c);
public static DcMotor.RunMode valueOf(java.lang.String name)
name
- the name of the enum constant to be returned.java.lang.IllegalArgumentException
- if this enum type has no constant with the specified namejava.lang.NullPointerException
- if the argument is null@Deprecated public DcMotor.RunMode migrate()
public boolean isPIDMode()