public class CANTalon extends Object implements MotorSafety, PIDOutput, PIDSource, CANSpeedController
| Modifier and Type | Class and Description |
|---|---|
static class |
CANTalon.FeedbackDevice |
static class |
CANTalon.FeedbackDeviceStatus
Depending on the sensor type, Talon can determine if sensor is plugged in ot not.
|
static class |
CANTalon.MotionProfileStatus
Motion Profile Status
This is simply a data transer object.
|
static class |
CANTalon.SetValueMotionProfile
Enumerated types for Motion Control Set Values.
|
static class |
CANTalon.StatusFrameRate
enumerated types for frame rate ms
|
static class |
CANTalon.TalonControlMode |
static class |
CANTalon.TrajectoryPoint
Motion Profile Trajectory Point
This is simply a data transer object.
|
CANSpeedController.ControlMode| Modifier and Type | Field and Description |
|---|---|
protected PIDSourceType |
m_pidSource |
DEFAULT_SAFETY_EXPIRATIONSMART_DASHBOARD_TYPE| Constructor and Description |
|---|
CANTalon(int deviceNumber)
Constructor for the CANTalon device.
|
CANTalon(int deviceNumber,
int controlPeriodMs)
Constructor for the CANTalon device.
|
CANTalon(int deviceNumber,
int controlPeriodMs,
int enablePeriodMs)
Constructor for the CANTalon device.
|
| Modifier and Type | Method and Description |
|---|---|
void |
changeControlMode(CANTalon.TalonControlMode controlMode) |
void |
changeMotionControlFramePeriod(int periodMs)
Calling application can opt to speed up the handshaking between the robot API and the Talon to increase the
download rate of the Talon's Motion Profile.
|
void |
clearIAccum() |
void |
ClearIaccum()
Clear the accumulator for I gain.
|
void |
clearMotionProfileHasUnderrun()
Clear the hasUnderrun flag in Talon's Motion Profile Executer when MPE is ready for another point,
but the low level buffer is empty.
|
void |
clearMotionProfileTrajectories()
Clear the buffered motion profile in both Talon RAM (bottom), and in the API (top).
|
void |
clearStickyFaults() |
void |
configEncoderCodesPerRev(int codesPerRev)
Configure how many codes per revolution are generated by your encoder.
|
void |
ConfigFwdLimitSwitchNormallyOpen(boolean normallyOpen)
Configure the fwd limit switch to be normally open or normally closed.
|
void |
configMaxOutputVoltage(double voltage)
Configure the maximum voltage that the Jaguar will ever output.
|
void |
configNominalOutputVoltage(double forwardVoltage,
double reverseVoltage) |
void |
configPeakOutputVoltage(double forwardVoltage,
double reverseVoltage) |
void |
configPotentiometerTurns(int turns)
Configure the number of turns on the potentiometer.
|
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 |
enable()
Allows the control loop to run.
|
void |
enableBrakeMode(boolean brake) |
void |
enableControl() |
void |
enableForwardSoftLimit(boolean enable) |
void |
enableLimitSwitch(boolean forward,
boolean reverse) |
void |
enableReverseSoftLimit(boolean enable) |
void |
enableZeroSensorPositionOnIndex(boolean enable,
boolean risingEdge)
Enables Talon SRX to automatically zero the Sensor Position whenever an
edge is detected on the index signal.
|
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()
Get the current input (battery) voltage.
|
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.TalonControlMode |
getControlMode()
Gets the current control mode.
|
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 |
getError()
Returns the difference between the setpoint and the current position.
|
double |
getExpiration() |
double |
getF()
Gets the feed-forward PID constant.
|
int |
getFaultForLim() |
int |
getFaultForSoftLim() |
int |
getFaultHardwareFailure() |
int |
getFaultOverTemp() |
int |
getFaultRevLim() |
int |
getFaultRevSoftLim() |
int |
getFaultUnderVoltage() |
long |
GetFirmwareVersion() |
int |
getForwardSoftLimit() |
double |
getI() |
long |
GetIaccum() |
boolean |
getInverted()
Common interface for the inverting direction of a speed controller.
|
double |
getIZone() |
void |
getMotionProfileStatus(CANTalon.MotionProfileStatus motionProfileStatus)
Retrieve all Motion Profile status information.
|
int |
getMotionProfileTopLevelBufferCount()
Retrieve just the buffer count for the api-level (top) buffer.
|
int |
getNumberOfQuadIdxRises()
Get the number of of rising edges seen on the index pin.
|
double |
getOutputCurrent()
Returns the current going through the Talon, in Amperes.
|
double |
getOutputVoltage()
Get the current output voltage.
|
double |
getP()
Get the current proportional constant.
|
double |
getParameter(CanTalonJNI.param_t paramEnum)
General get frame.
|
PIDSourceType |
getPIDSourceType()
Get which parameter of the device you are using as a process control
variable.
|
int |
getPinStateQuadA() |
int |
getPinStateQuadB() |
int |
getPinStateQuadIdx() |
double |
getPosition()
TODO documentation (see CANJaguar.java)
|
int |
getPulseWidthPosition() |
int |
getPulseWidthRiseToFallUs() |
int |
getPulseWidthRiseToRiseUs() |
int |
getPulseWidthVelocity() |
int |
getReverseSoftLimit() |
double |
getSetpoint() |
double |
getSpeed()
TODO documentation (see CANJaguar.java)
|
int |
getStickyFaultForLim() |
int |
getStickyFaultForSoftLim() |
int |
getStickyFaultOverTemp() |
int |
getStickyFaultRevLim() |
int |
getStickyFaultRevSoftLim() |
int |
getStickyFaultUnderVoltage() |
ITable |
getTable() |
double |
getTemperature()
Returns temperature of Talon, in degrees Celsius.
|
void |
initTable(ITable subtable)
Initializes a table for this sendable object.
|
boolean |
isAlive() |
boolean |
isControlEnabled() |
boolean |
isEnabled()
Return true if Talon is enabled.
|
boolean |
isForwardSoftLimitEnabled() |
boolean |
isFwdLimitSwitchClosed() |
boolean |
isMotionProfileTopLevelBufferFull() |
boolean |
isReverseSoftLimitEnabled() |
boolean |
isRevLimitSwitchClosed() |
boolean |
isSafetyEnabled() |
CANTalon.FeedbackDeviceStatus |
isSensorPresent(CANTalon.FeedbackDevice feedbackDevice) |
double |
pidGet()
Get the result to use in PIDController
$
|
void |
pidWrite(double output)
Set the output to the value calculated by PIDController
$
|
void |
processMotionProfileBuffer()
This must be called periodically to funnel the trajectory points from the API's top level buffer to
the Talon's bottom level buffer.
|
boolean |
pushMotionProfileTrajectory(CANTalon.TrajectoryPoint trajPt)
Push another trajectory point into the top level buffer (which is emptied into
the Talon's bottom buffer as room allows).
|
void |
reset()
Resets the accumulated integral error and disables the controller.
|
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 |
setAllowableClosedLoopErr(int allowableCloseLoopError)
Set the allowable closed loop error.
|
void |
setAnalogPosition(int newPosition) |
void |
setCloseLoopRampRate(double rampRate)
Set the closed loop ramp rate for the current profile.
|
void |
setControlMode(int mode)
Sets the control mode of this speed controller.
|
void |
setD(double d)
Set the derivative constant of the currently selected profile.
|
void |
setEncPosition(int newPosition) |
void |
setExpiration(double timeout) |
void |
setF(double f)
Set the feedforward value of the currently selected profile.
|
void |
setFeedbackDevice(CANTalon.FeedbackDevice device) |
void |
setForwardSoftLimit(double forwardLimit) |
void |
setI(double i)
Set the integration constant of the currently selected profile.
|
void |
setInverted(boolean isInverted)
Inverts the direction of the motor's rotation.
|
void |
setIZone(int izone)
Set the integration zone of the current Closed Loop profile.
|
protected void |
setMotionProfileStatusFromJNI(CANTalon.MotionProfileStatus motionProfileStatus,
int flags,
int profileSlotSelect,
int targPos,
int targVel,
int topBufferRem,
int topBufferCnt,
int btmBufferCnt,
int outputEnable)
Internal method to set the contents.
|
void |
setP(double p)
Set the proportional value of the currently selected profile.
|
void |
setParameter(CanTalonJNI.param_t paramEnum,
double value)
General set frame.
|
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 |
setPIDSourceType(PIDSourceType pidSource)
Set which parameter of the device you are using as a process control
variable.
|
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 |
setPulseWidthPosition(int newPosition) |
void |
setReverseSoftLimit(double reverseLimit) |
void |
setSafetyEnabled(boolean enabled) |
void |
setSetpoint(double setpoint)
Calls
set(double). |
void |
setStatusFrameRateMs(CANTalon.StatusFrameRate stateFrame,
int periodMs) |
void |
setVoltageCompensationRampRate(double rampRate) |
void |
setVoltageRampRate(double rampRate)
Set the voltage ramp rate for the current profile.
|
void |
startLiveWindowMode()
Start having this sendable object automatically respond to value changes
reflect the value on the table.
|
void |
stopLiveWindowMode()
Stop having this sendable object automatically respond to value changes.
|
void |
stopMotor()
Deprecated.
Use disableControl instead.
|
void |
updateTable()
Update the table for this sendable object with the latest values.
|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitcreateTableListener, getSmartDashboardTypeprotected PIDSourceType m_pidSource
public CANTalon(int deviceNumber)
deviceNumber - The CAN ID of the Talon SRXpublic CANTalon(int deviceNumber,
int controlPeriodMs)
deviceNumber - The CAN ID of the Talon SRXcontrolPeriodMs - The period in ms to send the CAN control frame.
Period is bounded to [1ms,95ms].public CANTalon(int deviceNumber,
int controlPeriodMs,
int enablePeriodMs)
deviceNumber - The CAN ID of the Talon SRXcontrolPeriodMs - The period in ms to send the CAN control frame.
Period is bounded to [1ms,95ms].enablePeriodMs - The period in ms to send the enable control frame.
Period is bounded to [1ms,95ms]. This typically is not
required to specify, however this could be used to minimize the
time between robot-enable and talon-motor-drive.public void pidWrite(double output)
PIDOutputpublic void setPIDSourceType(PIDSourceType pidSource)
setPIDSourceType in interface PIDSourcepidSource - An enum to select the parameter.public PIDSourceType getPIDSourceType()
getPIDSourceType in interface PIDSourcepublic double pidGet()
PIDSourcepublic void delete()
public void set(double outputValue)
set in interface SpeedControlleroutputValue - The setpoint value, as described above.public void setInverted(boolean isInverted)
setInverted in interface SpeedControllerisInverted - The state of inversion, true is inverted.public boolean getInverted()
getInverted in interface SpeedControllerpublic void set(double outputValue,
byte thisValueDoesNotDoAnything)
set in interface SpeedControlleroutputValue - See set().thisValueDoesNotDoAnything - corresponds to syncGroup from Jaguar; not
relevant here.public void reset()
PIDController.reset() is that
the PIDController also resets the previous error for the D term, but the
difference should have minimal effect as it will only last one cycle.reset in interface PIDInterfacepublic boolean isEnabled()
isEnabled in interface PIDInterfacepublic double getError()
getError in interface PIDInterfaceset() for a detailed description of the various units.public void setSetpoint(double setpoint)
set(double).setSetpoint in interface PIDInterfacepublic 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 SpeedControllerpublic int getEncPosition()
public void setEncPosition(int newPosition)
public int getEncVelocity()
public int getPulseWidthPosition()
public void setPulseWidthPosition(int newPosition)
public int getPulseWidthVelocity()
public int getPulseWidthRiseToFallUs()
public int getPulseWidthRiseToRiseUs()
public CANTalon.FeedbackDeviceStatus isSensorPresent(CANTalon.FeedbackDevice feedbackDevice)
feedbackDevice - which feedback sensor to check it if is connected.public int getNumberOfQuadIdxRises()
public int getPinStateQuadA()
public int getPinStateQuadB()
public int getPinStateQuadIdx()
public void setAnalogPosition(int newPosition)
public int getAnalogInPosition()
public int getAnalogInRaw()
public int getAnalogInVelocity()
public int getClosedLoopError()
public void setAllowableClosedLoopErr(int allowableCloseLoopError)
allowableCloseLoopError - allowable closed loop error for selected profile.
mA for Curent closed loop.
Talon Native Units for position and velocity.public boolean isFwdLimitSwitchClosed()
public boolean isRevLimitSwitchClosed()
public boolean getBrakeEnableDuringNeutral()
public void configEncoderCodesPerRev(int codesPerRev)
codesPerRev - The number of counts per revolution.public void configPotentiometerTurns(int turns)
turns - The number of turns of the potentiometer.public double getTemperature()
getTemperature in interface CANSpeedControllerpublic double getOutputCurrent()
getOutputCurrent in interface CANSpeedControllerpublic double getOutputVoltage()
CANSpeedControllergetOutputVoltage in interface CANSpeedControllerpublic double getBusVoltage()
CANSpeedControllergetBusVoltage in interface CANSpeedControllerpublic double getPosition()
getPosition in interface CANSpeedControllerpublic void setPosition(double pos)
public double getSpeed()
getSpeed in interface CANSpeedControllerpublic CANTalon.TalonControlMode getControlMode()
CANSpeedControllergetControlMode in interface CANSpeedControllerpublic void setControlMode(int mode)
CANSpeedControllersetControlMode in interface CANSpeedControllermode - the the new modepublic void changeControlMode(CANTalon.TalonControlMode controlMode)
public void setFeedbackDevice(CANTalon.FeedbackDevice device)
public void setStatusFrameRateMs(CANTalon.StatusFrameRate stateFrame, int periodMs)
public void enableControl()
public void enable()
enable in interface PIDInterfacepublic void disableControl()
public boolean isControlEnabled()
public double getP()
getP in interface PIDInterfacepublic double getI()
getI in interface PIDInterfacepublic double getD()
getD in interface PIDInterfacepublic double getF()
CANSpeedControllergetF in interface CANSpeedControllerpublic double getIZone()
public double getCloseLoopRampRate()
For selecting a certain profile.public long GetFirmwareVersion()
public long GetIaccum()
public void setP(double p)
setP in interface CANSpeedControllerp - Proportional constant for the currently selected PID profile.For selecting a certain profile.public void setI(double i)
setI in interface CANSpeedControlleri - Integration constant for the currently selected PID profile.For selecting a certain profile.public void setD(double d)
setD in interface CANSpeedControllerd - Derivative constant for the currently selected PID profile.For selecting a certain profile.public void setF(double f)
setF in interface CANSpeedControllerf - 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)
setVoltageRampRate in interface CANSpeedControllerrampRate - Maximum change in voltage, in volts / sec.public void setVoltageCompensationRampRate(double rampRate)
public void ClearIaccum()
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)
setPID in interface PIDInterfacepublic double getSetpoint()
getSetpoint in interface PIDInterfacepublic void setProfile(int profile)
public void stopMotor()
stopMotor in interface MotorSafetystopMotor in interface SpeedControllerpublic void disable()
SpeedControllerdisable in interface PIDInterfacedisable in interface SpeedControllerpublic int getDeviceID()
public void clearIAccum()
public void setForwardSoftLimit(double forwardLimit)
public int getForwardSoftLimit()
public void enableForwardSoftLimit(boolean enable)
public boolean isForwardSoftLimitEnabled()
public void setReverseSoftLimit(double reverseLimit)
public int getReverseSoftLimit()
public void enableReverseSoftLimit(boolean enable)
public boolean isReverseSoftLimitEnabled()
public void configMaxOutputVoltage(double voltage)
voltage - The maximum voltage output by the Jaguar.public void configPeakOutputVoltage(double forwardVoltage,
double reverseVoltage)
public void configNominalOutputVoltage(double forwardVoltage,
double reverseVoltage)
public void setParameter(CanTalonJNI.param_t paramEnum, double value)
public double getParameter(CanTalonJNI.param_t paramEnum)
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 enableZeroSensorPositionOnIndex(boolean enable,
boolean risingEdge)
enable - boolean input, pass true to enable feature or false to disable.risingEdge - boolean input, pass true to clear the position on rising edge,
pass false to clear the position on falling edge.public void changeMotionControlFramePeriod(int periodMs)
public void clearMotionProfileTrajectories()
public int getMotionProfileTopLevelBufferCount()
public boolean pushMotionProfileTrajectory(CANTalon.TrajectoryPoint trajPt)
targPos - servo position in native Talon units (sensor units).targVel - velocity to feed-forward in native Talon units (sensor units per 100ms).profileSlotSelect - which slot to pull PIDF gains from. Currently supports 0 or 1.timeDurMs - time in milliseconds of how long to apply this point.velOnly - set to nonzero to signal Talon that only the feed-foward velocity should be
used, i.e. do not perform PID on position. This is equivalent to setting
PID gains to zero, but much more efficient and synchronized to MP.isLastPoint - set to nonzero to signal Talon to keep processing this trajectory point,
instead of jumping to the next one when timeDurMs expires. Otherwise
MP executer will eventuall see an empty buffer after the last point expires,
causing it to assert the IsUnderRun flag. However this may be desired
if calling application nevers wants to terminate the MP.zeroPos - set to nonzero to signal Talon to "zero" the selected position sensor before executing
this trajectory point. Typically the first point should have this set only thus allowing
the remainder of the MP positions to be relative to zero.public boolean isMotionProfileTopLevelBufferFull()
public void processMotionProfileBuffer()
public void getMotionProfileStatus(CANTalon.MotionProfileStatus motionProfileStatus)
[out] - motionProfileStatus contains all progress information on the currently running MP. Caller should
must instantiate the motionProfileStatus object first then pass into this routine to be filled.protected void setMotionProfileStatusFromJNI(CANTalon.MotionProfileStatus motionProfileStatus, int flags, int profileSlotSelect, int targPos, int targVel, int topBufferRem, int topBufferCnt, int btmBufferCnt, int outputEnable)
public void clearMotionProfileHasUnderrun()
public void setExpiration(double timeout)
setExpiration in interface MotorSafetypublic double getExpiration()
getExpiration in interface MotorSafetypublic boolean isAlive()
isAlive in interface MotorSafetypublic boolean isSafetyEnabled()
isSafetyEnabled in interface MotorSafetypublic void setSafetyEnabled(boolean enabled)
setSafetyEnabled in interface MotorSafetypublic String getDescription()
getDescription in interface MotorSafetypublic void initTable(ITable subtable)
public void updateTable()
updateTable in interface CANSpeedControllerupdateTable in interface LiveWindowSendablepublic ITable getTable()
public void startLiveWindowMode()
startLiveWindowMode in interface LiveWindowSendablepublic void stopLiveWindowMode()
stopLiveWindowMode in interface LiveWindowSendable