public interface DcMotorController extends HardwareDevice
Different DC motor controllers will implement this interface.
| Modifier and Type | Interface and Description |
|---|---|
static class |
DcMotorController.DeviceMode
Deprecated.
This enumeration is deprecated as its use is no longer necessary. Any required mode
switching is handled automatically, under the covers.
|
static class |
DcMotorController.RunMode |
| Modifier and Type | Method and Description |
|---|---|
DcMotorController.RunMode |
getMotorChannelMode(int motor)
Get the current channel mode.
|
DcMotorController.DeviceMode |
getMotorControllerDeviceMode()
Deprecated.
This method is deprecated as its use is no longer necessary. Any required mode
switching is handled automatically, under the covers.
|
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)
Deprecated.
This method is deprecated as its use is no longer necessary. Any required mode
switching is handled automatically, under the covers.
|
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@Deprecated void setMotorControllerDeviceMode(DcMotorController.DeviceMode mode)
mode - device mode@Deprecated DcMotorController.DeviceMode getMotorControllerDeviceMode()
void setMotorChannelMode(int motor,
DcMotorController.RunMode mode)
DcMotorController.RunModemotor - 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