public class LynxDcMotorController extends LynxController
Modifier and Type | Class and Description |
---|---|
protected class |
LynxDcMotorController.MotorProperties |
LynxController.PretendLynxModule
Modifier and Type | Field and Description |
---|---|
static int |
apiMotorFirst |
static int |
apiMotorLast |
static double |
apiPowerFirst |
static double |
apiPowerLast |
protected static boolean |
DEBUG |
protected LynxDcMotorController.MotorProperties[] |
motors |
static java.lang.String |
TAG |
context, hardwareDeviceHealth, isEngaged, isHardwareInitialized, isHooked, registeredCallbacks
tag
Constructor and Description |
---|
LynxDcMotorController(android.content.Context context,
LynxModule module) |
Modifier and Type | Method and Description |
---|---|
protected void |
doHook() |
protected void |
doUnhook() |
void |
floatHardware() |
void |
forgetLastKnown() |
protected int |
getDefaultMaxMotorSpeed(int motorZ) |
java.lang.String |
getDeviceName() |
protected int |
getModuleAddress() |
double |
getMotorCurrent(int motor,
CurrentUnit unit) |
double |
getMotorCurrentAlert(int motor,
CurrentUnit unit) |
int |
getMotorCurrentPosition(int motor) |
DcMotor.RunMode |
getMotorMode(int motor) |
double |
getMotorPower(int motor) |
boolean |
getMotorPowerFloat(int motor) |
int |
getMotorTargetPosition(int motor) |
MotorConfigurationType |
getMotorType(int motor) |
double |
getMotorVelocity(int motor) |
double |
getMotorVelocity(int motor,
AngleUnit unit) |
DcMotor.ZeroPowerBehavior |
getMotorZeroPowerBehavior(int motor) |
PIDCoefficients |
getPIDCoefficients(int motor,
DcMotor.RunMode mode) |
PIDFCoefficients |
getPIDFCoefficients(int motor,
DcMotor.RunMode mode) |
protected java.lang.String |
getTag() |
void |
initializeHardware() |
protected DcMotor.RunMode |
internalGetMotorChannelMode(int motorZ)
like
internalGetPublicMotorMode(int) , but ALWAYS returns a value that can be set
with LynxSetMotorChannelModeCommand . |
protected DcMotor.RunMode |
internalGetPublicMotorMode(int motorZ) |
protected boolean |
internalSetPIDFCoefficients(int motorZ,
DcMotor.RunMode mode,
PIDFCoefficients pidfCoefficients) |
boolean |
isBusy(int motor) |
boolean |
isMotorEnabled(int motor) |
boolean |
isMotorOverCurrent(int motor) |
protected void |
rememberPIDParams(int motorZ,
ExpansionHubMotorControllerParamsState params) |
void |
resetDeviceConfigurationForOpMode(int motor) |
void |
setMotorCurrentAlert(int motor,
double current,
CurrentUnit unit) |
void |
setMotorDisable(int motor) |
void |
setMotorEnable(int motor) |
void |
setMotorMode(int motor,
DcMotor.RunMode mode) |
void |
setMotorPower(int motor,
double apiMotorPower) |
protected void |
setMotorPowerFloat(int motor) |
void |
setMotorTargetPosition(int motor,
int position) |
void |
setMotorTargetPosition(int motor,
int position,
int tolerance) |
void |
setMotorType(int motor,
MotorConfigurationType motorType) |
void |
setMotorVelocity(int motor,
double ticksPerSecond) |
void |
setMotorVelocity(int motor,
double angularRate,
AngleUnit unit) |
void |
setMotorZeroPowerBehavior(int motor,
DcMotor.ZeroPowerBehavior zeroPowerBehavior) |
void |
setPIDCoefficients(int motor,
DcMotor.RunMode mode,
PIDCoefficients pidCoefficients) |
void |
setPIDFCoefficients(int motor,
DcMotor.RunMode mode,
PIDFCoefficients pidfCoefficients) |
protected void |
updateMotorParams(int motorZ) |
adjustHookingToMatchEngagement, close, disengage, engage, finishConstruction, getArmingState, getConnectionInfo, getHealthStatus, getHealthStatusOverride, getManufacturer, getModule, getSerialNumber, getVersion, hook, isArmed, isEngaged, moduleNowArmedOrPretending, moduleNowDisarmed, onModuleStateChange, registerCallback, resetDeviceConfigurationForOpMode, setHealthStatus, setHealthyIfArmed, unhook, unregisterCallback
handleException, handleSpecificException, handleSpecificException
public static final int apiMotorFirst
public static final int apiMotorLast
public static final double apiPowerFirst
public static final double apiPowerLast
public static final java.lang.String TAG
protected static boolean DEBUG
protected final LynxDcMotorController.MotorProperties[] motors
public LynxDcMotorController(android.content.Context context, LynxModule module) throws RobotCoreException, java.lang.InterruptedException
RobotCoreException
java.lang.InterruptedException
protected java.lang.String getTag()
getTag
in class LynxController
public void initializeHardware() throws RobotCoreException, java.lang.InterruptedException
initializeHardware
in class LynxController
RobotCoreException
java.lang.InterruptedException
protected void doHook()
doHook
in class LynxController
protected void doUnhook()
doUnhook
in class LynxController
public void forgetLastKnown()
forgetLastKnown
in class LynxController
public java.lang.String getDeviceName()
getDeviceName
in class LynxController
public void setMotorEnable(int motor)
public void setMotorDisable(int motor)
public boolean isMotorEnabled(int motor)
public void resetDeviceConfigurationForOpMode(int motor)
public MotorConfigurationType getMotorType(int motor)
public void setMotorType(int motor, MotorConfigurationType motorType)
protected void rememberPIDParams(int motorZ, ExpansionHubMotorControllerParamsState params)
protected void updateMotorParams(int motorZ)
protected int getDefaultMaxMotorSpeed(int motorZ)
public void setMotorMode(int motor, DcMotor.RunMode mode)
public DcMotor.RunMode getMotorMode(int motor)
protected DcMotor.RunMode internalGetPublicMotorMode(int motorZ)
internalGetMotorChannelMode(int)
protected DcMotor.RunMode internalGetMotorChannelMode(int motorZ)
internalGetPublicMotorMode(int)
, but ALWAYS returns a value that can be set
with LynxSetMotorChannelModeCommand
. We also don't here update lastKnownMode.internalGetPublicMotorMode(int)
public void setMotorPower(int motor, double apiMotorPower)
public double getMotorPower(int motor)
public boolean isBusy(int motor)
public void setMotorZeroPowerBehavior(int motor, DcMotor.ZeroPowerBehavior zeroPowerBehavior)
public DcMotor.ZeroPowerBehavior getMotorZeroPowerBehavior(int motor)
protected void setMotorPowerFloat(int motor)
public boolean getMotorPowerFloat(int motor)
public void setMotorTargetPosition(int motor, int position)
public void setMotorTargetPosition(int motor, int position, int tolerance)
public int getMotorTargetPosition(int motor)
public int getMotorCurrentPosition(int motor)
public void setMotorVelocity(int motor, double ticksPerSecond)
public void setMotorVelocity(int motor, double angularRate, AngleUnit unit)
public double getMotorVelocity(int motor)
public double getMotorVelocity(int motor, AngleUnit unit)
public void setPIDCoefficients(int motor, DcMotor.RunMode mode, PIDCoefficients pidCoefficients)
public void setPIDFCoefficients(int motor, DcMotor.RunMode mode, PIDFCoefficients pidfCoefficients)
protected boolean internalSetPIDFCoefficients(int motorZ, DcMotor.RunMode mode, PIDFCoefficients pidfCoefficients)
public PIDCoefficients getPIDCoefficients(int motor, DcMotor.RunMode mode)
public PIDFCoefficients getPIDFCoefficients(int motor, DcMotor.RunMode mode)
public double getMotorCurrent(int motor, CurrentUnit unit)
public double getMotorCurrentAlert(int motor, CurrentUnit unit)
public void setMotorCurrentAlert(int motor, double current, CurrentUnit unit)
public boolean isMotorOverCurrent(int motor)
public void floatHardware()
floatHardware
in class LynxController
protected int getModuleAddress()