public class DcMotor extends java.lang.Object implements HardwareDevice
DcMotorController| Modifier and Type | Class and Description |
|---|---|
static class |
DcMotor.Direction
Motor direction
|
| Modifier and Type | Field and Description |
|---|---|
protected DcMotorController |
controller |
protected DcMotorController.DeviceMode |
devMode
Deprecated.
|
protected DcMotor.Direction |
direction |
protected DcMotorController.RunMode |
mode |
protected int |
portNumber |
| Constructor and Description |
|---|
DcMotor(DcMotorController controller,
int portNumber)
Constructor
|
DcMotor(DcMotorController controller,
int portNumber,
DcMotor.Direction direction)
Constructor
|
| Modifier and Type | Method and Description |
|---|---|
void |
close()
Close this device
|
DcMotorController.RunMode |
getChannelMode()
Deprecated.
|
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.
|
java.lang.String |
getDeviceName()
Device Name
|
DcMotor.Direction |
getDirection()
Get the direction
|
DcMotorController.RunMode |
getMode()
Get the current mode
|
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
|
protected void |
internalSetMode(DcMotorController.RunMode mode) |
protected void |
internalSetPower(double power) |
protected void |
internalSetTargetPosition(int position) |
boolean |
isBusy()
Is the motor busy?
|
void |
setChannelMode(DcMotorController.RunMode mode)
Deprecated.
|
void |
setDirection(DcMotor.Direction direction)
Set the direction
|
void |
setMode(DcMotorController.RunMode mode)
Set the current mode
|
void |
setPower(double power)
Set the current motor power
|
void |
setPowerFloat()
Allow motor to float
|
void |
setTargetPosition(int position)
Set the motor target position, using an integer.
|
protected DcMotor.Direction direction
protected DcMotorController controller
protected int portNumber
protected DcMotorController.RunMode mode
@Deprecated protected DcMotorController.DeviceMode devMode
public DcMotor(DcMotorController controller, int portNumber)
controller - DC motor controller this motor is attached toportNumber - portNumber position on the controllerpublic DcMotor(DcMotorController controller, int portNumber, DcMotor.Direction direction)
controller - DC motor controller this motor is attached toportNumber - portNumber port number on the controllerdirection - direction this motor should spinpublic java.lang.String getDeviceName()
HardwareDevicegetDeviceName in interface HardwareDevicepublic java.lang.String getConnectionInfo()
HardwareDevicegetConnectionInfo in interface HardwareDevicepublic int getVersion()
HardwareDevicegetVersion in interface HardwareDevicepublic void close()
HardwareDeviceclose in interface HardwareDevicepublic DcMotorController getController()
public void setDirection(DcMotor.Direction direction)
direction - directionpublic DcMotor.Direction getDirection()
public int getPortNumber()
public void setPower(double power)
power - from -1.0 to 1.0protected void internalSetPower(double power)
public double getPower()
public boolean isBusy()
public void setPowerFloat()
public boolean getPowerFloat()
public void setTargetPosition(int position)
position - range from Integer.MIN_VALUE to Integer.MAX_VALUEprotected void internalSetTargetPosition(int position)
public int getTargetPosition()
public int getCurrentPosition()
public void setMode(DcMotorController.RunMode mode)
mode - run modeprotected void internalSetMode(DcMotorController.RunMode mode)
public DcMotorController.RunMode getMode()
@Deprecated public void setChannelMode(DcMotorController.RunMode mode)
mode - run mode@Deprecated public DcMotorController.RunMode getChannelMode()