public class DcMotorImpl extends java.lang.Object implements DcMotor
DcMotorControllerDcMotor.RunMode, DcMotor.ZeroPowerBehaviorDcMotorSimple.DirectionHardwareDevice.Manufacturer| Modifier and Type | Field and Description |
|---|---|
protected DcMotorController |
controller |
protected DcMotorSimple.Direction |
direction |
protected MotorConfigurationType |
motorType |
protected int |
portNumber |
| Constructor and Description |
|---|
DcMotorImpl(DcMotorController controller,
int portNumber)
Constructor
|
DcMotorImpl(DcMotorController controller,
int portNumber,
DcMotorSimple.Direction direction)
Constructor
|
DcMotorImpl(DcMotorController controller,
int portNumber,
DcMotorSimple.Direction direction,
MotorConfigurationType motorType)
Constructor
|
| Modifier and Type | Method and Description |
|---|---|
protected int |
adjustPosition(int position) |
protected double |
adjustPower(double power) |
void |
close()
Closes this device
|
java.lang.String |
getConnectionInfo()
Get connection information about this device in a human readable format
|
DcMotorController |
getController()
Get DC motor controller
|
int |
getCurrentPosition()
Get the current encoder value, accommodating the configured directionality of the motor.
|
java.lang.String |
getDeviceName()
Returns a string suitable for display to the user as to the type of device.
|
DcMotorSimple.Direction |
getDirection()
Get the direction
|
HardwareDevice.Manufacturer |
getManufacturer()
Returns an indication of the manufacturer of this device.
|
DcMotor.RunMode |
getMode()
Get the current mode
|
MotorConfigurationType |
getMotorType()
Returns the assigned type for this motor.
|
protected DcMotorSimple.Direction |
getOperationalDirection() |
int |
getPortNumber()
Get port number
|
double |
getPower()
Get the current motor power
|
boolean |
getPowerFloat()
Is motor power set to float?
|
int |
getTargetPosition()
Get the current motor target position.
|
int |
getVersion()
Version
|
DcMotor.ZeroPowerBehavior |
getZeroPowerBehavior()
Returns the current behavior of the motor were a power level of zero to be applied.
|
protected void |
internalSetMode(DcMotor.RunMode mode) |
protected void |
internalSetPower(double power) |
protected void |
internalSetTargetPosition(int position) |
boolean |
isBusy()
Is the motor busy?
|
void |
resetDeviceConfigurationForOpMode()
Resets the device's configuration to that which is expected at the beginning of an OpMode.
|
void |
setDirection(DcMotorSimple.Direction direction)
Set the direction
|
void |
setMode(DcMotor.RunMode mode)
Set the current mode
|
void |
setMotorType(MotorConfigurationType motorType)
Sets the assigned type of this motor.
|
void |
setPower(double power)
Set the current motor power
|
void |
setPowerFloat()
Deprecated.
|
void |
setTargetPosition(int position)
Set the motor target position, using an integer.
|
void |
setZeroPowerBehavior(DcMotor.ZeroPowerBehavior zeroPowerBehavior)
Sets the behavior of the motor when a power level of zero is applied.
|
protected DcMotorController controller
protected int portNumber
protected DcMotorSimple.Direction direction
protected MotorConfigurationType motorType
public DcMotorImpl(DcMotorController controller, int portNumber)
controller - DC motor controller this motor is attached toportNumber - portNumber position on the controllerpublic DcMotorImpl(DcMotorController controller, int portNumber, DcMotorSimple.Direction direction)
controller - DC motor controller this motor is attached toportNumber - portNumber port number on the controllerdirection - direction this motor should spinpublic DcMotorImpl(DcMotorController controller, int portNumber, DcMotorSimple.Direction direction, MotorConfigurationType motorType)
controller - DC motor controller this motor is attached toportNumber - portNumber port number on the controllerdirection - direction this motor should spinmotorType - the type we know this motor to bepublic HardwareDevice.Manufacturer getManufacturer()
HardwareDevicegetManufacturer in interface HardwareDevicepublic java.lang.String getDeviceName()
HardwareDevicegetDeviceName in interface HardwareDevicepublic java.lang.String getConnectionInfo()
HardwareDevicegetConnectionInfo in interface HardwareDevicepublic int getVersion()
HardwareDevicegetVersion in interface HardwareDevicepublic void resetDeviceConfigurationForOpMode()
HardwareDeviceresetDeviceConfigurationForOpMode in interface HardwareDevicepublic void close()
HardwareDeviceclose in interface HardwareDevicepublic MotorConfigurationType getMotorType()
DcMotorMotorConfigurationType.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.getMotorType in interface DcMotorpublic void setMotorType(MotorConfigurationType motorType)
DcMotorsetMotorType in interface DcMotormotorType - the new assigned type for this motorDcMotor.getMotorType()public DcMotorController getController()
getController in interface DcMotorDcMotor.getPortNumber()public void setDirection(DcMotorSimple.Direction direction)
setDirection in interface DcMotorSimpledirection - directionDcMotorSimple.getDirection()public DcMotorSimple.Direction getDirection()
getDirection in interface DcMotorSimpleDcMotorSimple.setDirection(Direction)public int getPortNumber()
getPortNumber in interface DcMotorDcMotor.getController()public void setPower(double power)
setPower in interface DcMotorSimplepower - from -1.0 to 1.0DcMotorSimple.getPower(),
DcMotor.setMode(DcMotor.RunMode),
DcMotor.setPowerFloat()protected void internalSetPower(double power)
public double getPower()
getPower in interface DcMotorSimpleDcMotorSimple.setPower(double)public boolean isBusy()
isBusy in interface DcMotorDcMotor.setTargetPosition(int)public void setZeroPowerBehavior(DcMotor.ZeroPowerBehavior zeroPowerBehavior)
DcMotorsetZeroPowerBehavior in interface DcMotorzeroPowerBehavior - the new behavior of the motor when a power level of zero is applied.DcMotor.ZeroPowerBehavior,
DcMotorSimple.setPower(double)public DcMotor.ZeroPowerBehavior getZeroPowerBehavior()
DcMotorgetZeroPowerBehavior in interface DcMotor@Deprecated public void setPowerFloat()
setPowerFloat in interface DcMotorDcMotorSimple.setPower(double),
DcMotor.getPowerFloat(),
DcMotor.setZeroPowerBehavior(ZeroPowerBehavior)public boolean getPowerFloat()
getPowerFloat in interface DcMotorDcMotor.setPowerFloat()public void setTargetPosition(int position)
setTargetPosition in interface DcMotorposition - range from Integer.MIN_VALUE to Integer.MAX_VALUEDcMotor.getCurrentPosition(),
DcMotor.setMode(RunMode),
DcMotor.RunMode.RUN_TO_POSITION,
DcMotor.getTargetPosition(),
DcMotor.isBusy()protected void internalSetTargetPosition(int position)
public int getTargetPosition()
getTargetPosition in interface DcMotorDcMotor.setTargetPosition(int)public int getCurrentPosition()
getCurrentPosition in interface DcMotorDcMotor.getTargetPosition(),
DcMotor.RunMode.STOP_AND_RESET_ENCODERprotected int adjustPosition(int position)
protected double adjustPower(double power)
protected DcMotorSimple.Direction getOperationalDirection()
public void setMode(DcMotor.RunMode mode)
setMode in interface DcMotormode - run modeDcMotor.RunMode,
DcMotor.getMode()protected void internalSetMode(DcMotor.RunMode mode)
public DcMotor.RunMode getMode()
getMode in interface DcMotorDcMotor.RunMode,
DcMotor.setMode(RunMode)