public interface DcMotorController extends HardwareDevice
Different DC motor controllers will implement this interface.
Modifier and Type | Interface and Description |
---|---|
static class |
DcMotorController.DeviceMode |
static class |
DcMotorController.RunMode |
Modifier and Type | Method and Description |
---|---|
DcMotorController.RunMode |
getMotorChannelMode(int motor)
Get the current channel mode.
|
DcMotorController.DeviceMode |
getMotorControllerDeviceMode()
Get the current device mode (read, write, or read/write)
Note: on USB devices, this will always return "READ_WRITE" mode.
|
int |
getMotorCurrentPosition(int motor)
Get the current motor position
|
double |
getMotorPower(int motor)
Get the current motor power
|
boolean |
getMotorPowerFloat(int motor)
Is motor power set to float?
|
int |
getMotorTargetPosition(int motor)
Get the current motor target position
|
boolean |
isBusy(int motor)
Is the motor busy?
|
void |
setMotorChannelMode(int motor,
DcMotorController.RunMode mode)
Set the current channel mode.
|
void |
setMotorControllerDeviceMode(DcMotorController.DeviceMode mode)
Set the device into read, write, or read/write modes
Note: If you are using the NxtDcMotorController, you need to switch the controller into "read" mode
before doing a read, and into "write" mode before doing a write.
|
void |
setMotorPower(int motor,
double power)
Set the current motor power
|
void |
setMotorPowerFloat(int motor)
Allow motor to float
|
void |
setMotorTargetPosition(int motor,
int position)
Set the motor target position.
|
close, getConnectionInfo, getDeviceName, getVersion
void setMotorControllerDeviceMode(DcMotorController.DeviceMode mode)
mode
- device modeDcMotorController.DeviceMode getMotorControllerDeviceMode()
void setMotorChannelMode(int motor, DcMotorController.RunMode mode)
DcMotorController.RunMode
motor
- port of motormode
- run modeDcMotorController.RunMode getMotorChannelMode(int motor)
motor
- port of motorvoid setMotorPower(int motor, double power)
motor
- port of motorpower
- from -1.0 to 1.0double getMotorPower(int motor)
motor
- port of motorboolean isBusy(int motor)
motor
- port of motorvoid setMotorPowerFloat(int motor)
motor
- port of motorboolean getMotorPowerFloat(int motor)
motor
- port of motorvoid setMotorTargetPosition(int motor, int position)
motor
- port of motorposition
- range from Integer.MIN_VALUE to Integer.MAX_VALUEint getMotorTargetPosition(int motor)
motor
- port of motorint getMotorCurrentPosition(int motor)
motor
- port of motor