public class CANTalon extends Object implements MotorSafety, PIDOutput, SpeedController
Modifier and Type | Class and Description |
---|---|
static class |
CANTalon.ControlMode |
static class |
CANTalon.FeedbackDevice |
static class |
CANTalon.StatusFrameRate
enumerated types for frame rate ms
|
DEFAULT_SAFETY_EXPIRATION
Constructor and Description |
---|
CANTalon(int deviceNumber) |
CANTalon(int deviceNumber,
int controlPeriodMs) |
Modifier and Type | Method and Description |
---|---|
void |
changeControlMode(CANTalon.ControlMode controlMode) |
void |
ClearIaccum()
Clear the accumulator for I gain.
|
void |
clearStickyFaults() |
void |
ConfigFwdLimitSwitchNormallyOpen(boolean normallyOpen)
Configure the fwd limit switch to be normally open or normally closed.
|
void |
ConfigRevLimitSwitchNormallyOpen(boolean normallyOpen)
Configure the rev limit switch to be normally open or normally closed.
|
void |
delete() |
void |
disable()
Disable the speed controller
|
void |
disableControl() |
void |
enableBrakeMode(boolean brake) |
void |
enableControl() |
void |
enableForwardSoftLimit(boolean enable) |
void |
enableLimitSwitch(boolean forward,
boolean reverse) |
void |
enableReverseSoftLimit(boolean enable) |
double |
get()
Gets the current status of the Talon (usually a sensor value).
|
int |
getAnalogInPosition()
Get the current analog in position, regardless of whether it is the current
feedback device.
|
int |
getAnalogInRaw()
Get the current analog in position, regardless of whether it is the current
feedback device.
|
int |
getAnalogInVelocity()
Get the current encoder velocity, regardless of whether it is the current
feedback device.
|
boolean |
getBrakeEnableDuringNeutral() |
double |
getBusVoltage() |
int |
getClosedLoopError()
Get the current difference between the setpoint and the sensor value.
|
double |
getCloseLoopRampRate()
Get the closed loop ramp rate for the current profile.
|
CANTalon.ControlMode |
getControlMode() |
double |
getD() |
String |
getDescription() |
int |
getDeviceID() |
int |
getEncPosition()
Get the current encoder position, regardless of whether it is the current feedback device.
|
int |
getEncVelocity()
Get the current encoder velocity, regardless of whether it is the current feedback device.
|
double |
getExpiration() |
double |
getF() |
int |
getFaultForLim() |
int |
getFaultForSoftLim() |
int |
getFaultHardwareFailure() |
int |
getFaultOverTemp() |
int |
getFaultRevLim() |
int |
getFaultRevSoftLim() |
int |
getFaultUnderVoltage() |
long |
GetFirmwareVersion() |
double |
getI() |
long |
GetIaccum() |
double |
getIZone() |
int |
getNumberOfQuadIdxRises()
Get the number of of rising edges seen on the index pin.
|
double |
getOutputCurrent() |
double |
getOutputVoltage() |
double |
getP()
Get the current proportional constant.
|
int |
getPinStateQuadA() |
int |
getPinStateQuadB() |
int |
getPinStateQuadIdx() |
double |
getPosition() |
double |
getSetpoint() |
double |
getSpeed() |
int |
getStickyFaultForLim() |
int |
getStickyFaultForSoftLim() |
int |
getStickyFaultOverTemp() |
int |
getStickyFaultRevLim() |
int |
getStickyFaultRevSoftLim() |
int |
getStickyFaultUnderVoltage() |
double |
getTemp() |
boolean |
isAlive() |
boolean |
isControlEnabled() |
boolean |
isFwdLimitSwitchClosed() |
boolean |
isRevLimitSwitchClosed() |
boolean |
isSafetyEnabled() |
void |
pidWrite(double output)
Set the output to the value calculated by PIDController
|
void |
reverseOutput(boolean flip)
Flips the sign (multiplies by negative one) the throttle values going into
the motor on the talon in closed loop modes.
|
void |
reverseSensor(boolean flip)
Flips the sign (multiplies by negative one) the sensor values going into
the talon.
|
void |
set(double outputValue)
Sets the appropriate output on the talon, depending on the mode.
|
void |
set(double outputValue,
byte thisValueDoesNotDoAnything)
Sets the output of the Talon.
|
void |
setCloseLoopRampRate(double rampRate)
Set the closed loop ramp rate for the current profile.
|
void |
setD(double d)
Set the derivative constant of the currently selected profile.
|
void |
setExpiration(double timeout) |
void |
setF(double f)
Set the feedforward value of the currently selected profile.
|
void |
setFeedbackDevice(CANTalon.FeedbackDevice device) |
void |
setForwardSoftLimit(int forwardLimit) |
void |
setI(double i)
Set the integration constant of the currently selected profile.
|
void |
setIZone(int izone)
Set the integration zone of the current Closed Loop profile.
|
void |
setP(double p)
Set the proportional value of the currently selected profile.
|
void |
setPID(double p,
double i,
double d) |
void |
setPID(double p,
double i,
double d,
double f,
int izone,
double closeLoopRampRate,
int profile)
Sets control values for closed loop control.
|
void |
setPosition(double pos) |
void |
setProfile(int profile)
Select which closed loop profile to use, and uses whatever PIDF gains and
the such that are already there.
|
void |
setReverseSoftLimit(int reverseLimit) |
void |
setSafetyEnabled(boolean enabled) |
void |
setStatusFrameRateMs(CANTalon.StatusFrameRate stateFrame,
int periodMs) |
void |
setVoltageRampRate(double rampRate)
Set the voltage ramp rate for the current profile.
|
void |
stopMotor()
Deprecated.
Use disableControl instead.
|
public CANTalon(int deviceNumber)
public CANTalon(int deviceNumber, int controlPeriodMs)
public void pidWrite(double output)
PIDOutput
public void delete()
public void set(double outputValue)
set
in interface SpeedController
outputValue
- The setpoint value, as described above.public void set(double outputValue, byte thisValueDoesNotDoAnything)
set
in interface SpeedController
outputValue
- See set().thisValueDoesNotDoAnything
- corresponds to syncGroup from Jaguar; not relevant here.public void reverseSensor(boolean flip)
flip
- True if sensor input should be flipped; False if not.public void reverseOutput(boolean flip)
flip
- True if motor output should be flipped; False if not.public double get()
get
in interface SpeedController
public int getEncPosition()
public int getEncVelocity()
public int getNumberOfQuadIdxRises()
public int getPinStateQuadA()
public int getPinStateQuadB()
public int getPinStateQuadIdx()
public int getAnalogInPosition()
public int getAnalogInRaw()
public int getAnalogInVelocity()
public int getClosedLoopError()
public boolean isFwdLimitSwitchClosed()
public boolean isRevLimitSwitchClosed()
public boolean getBrakeEnableDuringNeutral()
public double getTemp()
public double getOutputCurrent()
public double getOutputVoltage()
public double getBusVoltage()
public double getPosition()
public void setPosition(double pos)
public double getSpeed()
public CANTalon.ControlMode getControlMode()
public void changeControlMode(CANTalon.ControlMode controlMode)
public void setFeedbackDevice(CANTalon.FeedbackDevice device)
public void setStatusFrameRateMs(CANTalon.StatusFrameRate stateFrame, int periodMs)
public void enableControl()
public void disableControl()
public boolean isControlEnabled()
public double getP()
IllegalStateException
- if not in Position of Speed mode.public double getI()
public double getD()
public double getF()
public double getIZone()
public double getCloseLoopRampRate()
For selecting a certain profile.
public long GetFirmwareVersion()
public long GetIaccum()
public void ClearIaccum()
public void setP(double p)
p
- Proportional constant for the currently selected PID profile.For selecting a certain profile.
public void setI(double i)
i
- Integration constant for the currently selected PID profile.For selecting a certain profile.
public void setD(double d)
d
- Derivative constant for the currently selected PID profile.For selecting a certain profile.
public void setF(double f)
f
- Feedforward constant for the currently selected PID profile.For selecting a certain profile.
public void setIZone(int izone)
izone
- Width of the integration zone.For selecting a certain profile.
public void setCloseLoopRampRate(double rampRate)
rampRate
- Maximum change in voltage, in volts / sec.For selecting a certain profile.
public void setVoltageRampRate(double rampRate)
rampRate
- Maximum change in voltage, in volts / sec.public void setPID(double p, double i, double d, double f, int izone, double closeLoopRampRate, int profile)
p
- Proportional constant.i
- Integration constant.d
- Differential constant.f
- Feedforward constant.izone
- Integration zone -- prevents accumulation of integration error
with large errors. Setting this to zero will ignore any izone stuff.closeLoopRampRate
- Closed loop ramp rate. Maximum change in voltage, in volts / sec.profile
- which profile to set the pid constants for. You can have two
profiles, with values of 0 or 1, allowing you to keep a second set of values
on hand in the talon. In order to switch profiles without recalling setPID,
you must call setProfile().public void setPID(double p, double i, double d)
public double getSetpoint()
public void setProfile(int profile)
@Deprecated public void stopMotor()
stopMotor
in interface MotorSafety
public void disable()
SpeedController
disable
in interface SpeedController
public int getDeviceID()
public void setForwardSoftLimit(int forwardLimit)
public void enableForwardSoftLimit(boolean enable)
public void setReverseSoftLimit(int reverseLimit)
public void enableReverseSoftLimit(boolean enable)
public void clearStickyFaults()
public void enableLimitSwitch(boolean forward, boolean reverse)
public void ConfigFwdLimitSwitchNormallyOpen(boolean normallyOpen)
normallyOpen
- true for normally open. false for normally closed.public void ConfigRevLimitSwitchNormallyOpen(boolean normallyOpen)
normallyOpen
- true for normally open. false for normally closed.public void enableBrakeMode(boolean brake)
public int getFaultOverTemp()
public int getFaultUnderVoltage()
public int getFaultForLim()
public int getFaultRevLim()
public int getFaultHardwareFailure()
public int getFaultForSoftLim()
public int getFaultRevSoftLim()
public int getStickyFaultOverTemp()
public int getStickyFaultUnderVoltage()
public int getStickyFaultForLim()
public int getStickyFaultRevLim()
public int getStickyFaultForSoftLim()
public int getStickyFaultRevSoftLim()
public void setExpiration(double timeout)
setExpiration
in interface MotorSafety
public double getExpiration()
getExpiration
in interface MotorSafety
public boolean isAlive()
isAlive
in interface MotorSafety
public boolean isSafetyEnabled()
isSafetyEnabled
in interface MotorSafety
public void setSafetyEnabled(boolean enabled)
setSafetyEnabled
in interface MotorSafety
public String getDescription()
getDescription
in interface MotorSafety
Copyright © 2015. All rights reserved.