public class CANTalon extends java.lang.Object implements edu.wpi.first.wpilibj.MotorSafety, edu.wpi.first.wpilibj.PIDOutput, edu.wpi.first.wpilibj.PIDSource, edu.wpi.first.wpilibj.CANSpeedController, GadgeteerUartClient
| 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.
|
static class |
CANTalon.VelocityMeasurementPeriod
Enumerated types for velocity measurement period ms.
|
edu.wpi.first.wpilibj.CANSpeedController.ControlModeGadgeteerUartClient.GadgeteerConnection, GadgeteerUartClient.GadgeteerProxyType, GadgeteerUartClient.GadgeteerState, GadgeteerUartClient.GadgeteerUartStatus| Modifier and Type | Field and Description |
|---|---|
protected edu.wpi.first.wpilibj.PIDSourceType |
m_pidSource |
| 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() |
void |
disableControl() |
void |
DisableNominalClosedLoopVoltage()
Disables the nominal closed loop voltage compensation.
|
void |
enable() |
void |
enableBrakeMode(boolean brake) |
void |
enableControl() |
void |
EnableCurrentLimit(boolean enable) |
void |
enableForwardSoftLimit(boolean enable) |
void |
enableLimitSwitch(boolean forward,
boolean reverse) |
void |
enableReverseSoftLimit(boolean enable) |
void |
enableZeroSensorPositionOnForwardLimit(boolean enable)
Enables Talon SRX to automatically zero the Sensor Position whenever an edge is detected on the
Forward Limit Switch signal.
|
void |
enableZeroSensorPositionOnIndex(boolean enable,
boolean risingEdge)
Enables Talon SRX to automatically zero the Sensor Position whenever an edge is detected on the
index signal.
|
void |
enableZeroSensorPositionOnReverseLimit(boolean enable)
Enables Talon SRX to automatically zero the Sensor Position whenever an edge is detected on the
Reverse Limit Switch 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() |
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() |
double |
getD() |
java.lang.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() |
int |
getFaultForLim() |
int |
getFaultForSoftLim() |
int |
getFaultHardwareFailure() |
int |
getFaultOverTemp() |
int |
getFaultRevLim() |
int |
getFaultRevSoftLim() |
int |
getFaultUnderVoltage() |
long |
GetFirmwareVersion()
Firmware version running on the Talon.
|
int |
getForwardSoftLimit() |
int |
GetGadgeteerStatus(GadgeteerUartClient.GadgeteerUartStatus status) |
double |
getI() |
long |
GetIaccum() |
boolean |
getInverted()
Common interface for the inverting direction of a speed controller.
|
double |
getIZone() |
java.lang.String |
getLastError() |
double |
getMotionMagicAcceleration() |
double |
getMotionMagicCruiseVelocity() |
void |
getMotionProfileStatus(CANTalon.MotionProfileStatus motionProfileStatus)
Retrieve all Motion Profile status information.
|
int |
getMotionProfileTopLevelBufferCount()
Retrieve just the buffer count for the api-level (top) buffer.
|
double |
GetNominalClosedLoopVoltage() |
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() |
double |
getP()
Get the current proportional constant.
|
double |
getParameter(com.ctre.CanTalonJNI.param_t paramEnum)
General get frame.
|
edu.wpi.first.wpilibj.PIDSourceType |
getPIDSourceType() |
int |
getPinStateQuadA() |
int |
getPinStateQuadB() |
int |
getPinStateQuadIdx() |
double |
getPosition()
When using analog sensors, 0 units corresponds to 0V, 1023 units corresponds to 3.3V When using
an analog encoder (wrapping around 1023 to 0 is possible) the units are still 3.3V per 1023
units.
|
int |
getPulseWidthPosition() |
int |
getPulseWidthRiseToFallUs() |
int |
getPulseWidthRiseToRiseUs() |
int |
getPulseWidthVelocity() |
int |
getReverseSoftLimit() |
double |
getSetpoint() |
double |
getSpeed()
The speed units will be in the sensor's native ticks per 100ms.
|
int |
getStickyFaultForLim() |
int |
getStickyFaultForSoftLim() |
int |
getStickyFaultOverTemp() |
int |
getStickyFaultRevLim() |
int |
getStickyFaultRevSoftLim() |
int |
getStickyFaultUnderVoltage() |
edu.wpi.first.wpilibj.tables.ITable |
getTable() |
double |
getTemperature()
Returns temperature of Talon, in degrees Celsius.
|
CANTalon.VelocityMeasurementPeriod |
GetVelocityMeasurementPeriod() |
int |
GetVelocityMeasurementWindow() |
void |
initTable(edu.wpi.first.wpilibj.tables.ITable subtable) |
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) |
boolean |
isZeroSensorPosOnFwdLimitEnabled() |
boolean |
isZeroSensorPosOnIndexEnabled() |
boolean |
isZeroSensorPosOnRevLimitEnabled() |
double |
pidGet() |
void |
pidWrite(double output) |
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 |
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) |
void |
setCurrentLimit(int amps) |
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.
|
void |
setMotionMagicAcceleration(double motMagicAccel)
Set the Acceleration used in Motion Magic Control Mode.
|
void |
setMotionMagicCruiseVelocity(double motMagicCruiseVeloc)
Set the Cruise Velocity used in Motion Magic Control Mode.
|
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 |
setNominalClosedLoopVoltage(double voltage) |
void |
setP(double p)
Set the proportional value of the currently selected profile.
|
void |
setParameter(com.ctre.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(edu.wpi.first.wpilibj.PIDSourceType pidSource) |
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 |
SetVelocityMeasurementPeriod(CANTalon.VelocityMeasurementPeriod period)
Sets the duration of time that the Talon measures for each velocity measurement (which occures at each 1ms process loop).
|
void |
SetVelocityMeasurementWindow(int windowSize)
Sets the window size of the rolling average used in velocity measurement.
|
void |
setVoltageCompensationRampRate(double rampRate) |
void |
setVoltageRampRate(double rampRate)
Set the voltage ramp rate for the current profile.
|
void |
startLiveWindowMode() |
void |
stopLiveWindowMode() |
void |
stopMotor()
Deprecated.
Use disableControl instead.
|
void |
updateTable() |
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)
pidWrite in interface edu.wpi.first.wpilibj.PIDOutputpublic void setPIDSourceType(edu.wpi.first.wpilibj.PIDSourceType pidSource)
setPIDSourceType in interface edu.wpi.first.wpilibj.PIDSourcepublic edu.wpi.first.wpilibj.PIDSourceType getPIDSourceType()
getPIDSourceType in interface edu.wpi.first.wpilibj.PIDSourcepublic double pidGet()
pidGet in interface edu.wpi.first.wpilibj.PIDSourcepublic void delete()
public void set(double outputValue)
In PercentVbus, the output is between -1.0 and 1.0, with 0.0 as stopped. In Follower mode, the output is the integer device ID of the talon to duplicate. In Voltage mode, outputValue is in volts. In Current mode, outputValue is in amperes. In Speed mode, outputValue is in position change / 10ms. In Position mode, outputValue is in encoder ticks or an analog value, depending on the sensor.
set in interface edu.wpi.first.wpilibj.SpeedControlleroutputValue - The setpoint value, as described above.public void setInverted(boolean isInverted)
setInverted in interface edu.wpi.first.wpilibj.SpeedControllerisInverted - The state of inversion, true is inverted.public boolean getInverted()
getInverted in interface edu.wpi.first.wpilibj.SpeedControllerpublic void reset()
The only difference between this and 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 edu.wpi.first.wpilibj.PIDInterfacepublic boolean isEnabled()
isEnabled in interface edu.wpi.first.wpilibj.PIDInterfacepublic double getError()
getError in interface edu.wpi.first.wpilibj.PIDInterfaceset() for a detailed description of the various units.public void setSetpoint(double setpoint)
set(double).setSetpoint in interface edu.wpi.first.wpilibj.PIDInterfacepublic void reverseSensor(boolean flip)
This only affects position and velocity closed loop control. Allows for situations where you may have a sensor flipped and going in the wrong direction.
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()
In Current mode: returns output current. In Speed mode: returns current speed. In Position mode: returns current sensor position. In PercentVbus and Follower modes: returns current applied throttle.
get in interface edu.wpi.first.wpilibj.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()
The bottom ten bits is the ADC (0 - 1023) on the analog pin of the Talon. The upper 14 bits tracks the overflows and underflows (continuous sensor).
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 isZeroSensorPosOnIndexEnabled()
public boolean isZeroSensorPosOnRevLimitEnabled()
public boolean isZeroSensorPosOnFwdLimitEnabled()
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 edu.wpi.first.wpilibj.CANSpeedControllerpublic double getOutputCurrent()
getOutputCurrent in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic double getOutputVoltage()
getOutputVoltage in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic double getBusVoltage()
getBusVoltage in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic double getPosition()
getPosition in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic void setPosition(double pos)
public double getSpeed()
For analog sensors, 3.3V corresponds to 1023 units. So a speed of 200 equates to ~0.645 dV per 100ms or 6.451 dV per second. If this is an analog encoder, that likely means 1.9548 rotations per sec. For quadrature encoders, each unit corresponds a quadrature edge (4X). So a 250 count encoder will produce 1000 edge events per rotation. An example speed of 200 would then equate to 20% of a rotation per 100ms, or 10 rotations per second.
getSpeed in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic CANTalon.TalonControlMode getControlMode()
getControlMode in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic void setControlMode(int mode)
setControlMode in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic 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 edu.wpi.first.wpilibj.PIDInterfacepublic void disableControl()
public boolean isControlEnabled()
public double getP()
getP in interface edu.wpi.first.wpilibj.PIDInterfacepublic double getI()
getI in interface edu.wpi.first.wpilibj.PIDInterfacepublic double getD()
getD in interface edu.wpi.first.wpilibj.PIDInterfacepublic double getF()
getF in interface edu.wpi.first.wpilibj.CANSpeedControllerpublic double getIZone()
public double getCloseLoopRampRate()
Limits the rate at which the throttle will change. Only affects position and speed closed loop modes.
For selecting a certain profile.public long GetFirmwareVersion()
public long GetIaccum()
public void setP(double p)
setP in interface edu.wpi.first.wpilibj.CANSpeedControllerp - Proportional constant for the currently selected PID profile.For selecting a certain profile.public void setI(double i)
setI in interface edu.wpi.first.wpilibj.CANSpeedControlleri - Integration constant for the currently selected PID profile.For selecting a certain profile.public void setD(double d)
setD in interface edu.wpi.first.wpilibj.CANSpeedControllerd - Derivative constant for the currently selected PID profile.For selecting a certain profile.public void setF(double f)
setF in interface edu.wpi.first.wpilibj.CANSpeedControllerf - Feedforward constant for the currently selected PID profile.For selecting a certain profile.public void setIZone(int izone)
Whenever the error is larger than the izone value, the accumulated integration error is cleared so that high errors aren't racked up when at high errors. An izone value of 0 means no difference from a standard PIDF loop.
izone - Width of the integration zone.For selecting a certain profile.public void setCloseLoopRampRate(double rampRate)
Limits the rate at which the throttle will change. Only affects position and speed closed loop modes.
rampRate - Maximum change in voltage, in volts / sec.For selecting a certain profile.public void setVoltageRampRate(double rampRate)
Limits the rate at which the throttle will change. Affects all modes.
setVoltageRampRate in interface edu.wpi.first.wpilibj.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 edu.wpi.first.wpilibj.PIDInterfacepublic double getSetpoint()
getSetpoint in interface edu.wpi.first.wpilibj.PIDInterfacepublic void setProfile(int profile)
@Deprecated public void stopMotor()
stopMotor in interface edu.wpi.first.wpilibj.MotorSafetystopMotor in interface edu.wpi.first.wpilibj.SpeedControllerpublic void disable()
disable in interface edu.wpi.first.wpilibj.PIDInterfacedisable in interface edu.wpi.first.wpilibj.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)
This can be used to limit the maximum output voltage in all modes so that motors which cannot withstand full bus voltage can be used safely.
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(com.ctre.CanTalonJNI.param_t paramEnum,
double value)
public double getParameter(com.ctre.CanTalonJNI.param_t paramEnum)
public void clearStickyFaults()
public void enableLimitSwitch(boolean forward,
boolean reverse)
public void ConfigFwdLimitSwitchNormallyOpen(boolean normallyOpen)
Since Talon saves setting to flash this should only affect a given Talon initially during robot install.
normallyOpen - true for normally open. false for normally closed.public void ConfigRevLimitSwitchNormallyOpen(boolean normallyOpen)
Since Talon saves setting to flash this should only affect a given Talon initially during robot install.
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 enableZeroSensorPositionOnForwardLimit(boolean enable)
enable - boolean input, pass true to enable feature or false to disable.public void enableZeroSensorPositionOnReverseLimit(boolean enable)
enable - boolean input, pass true to enable feature or false to disable.public void setNominalClosedLoopVoltage(double voltage)
voltage - Motor voltage to output when closed loop features are being used (Position,
Speed, Motion Profile, Motion Magic, etc.) in volts.
Pass 0 to disable feature. Input should be within [0.0 V,255.0 V]public void DisableNominalClosedLoopVoltage()
public double GetNominalClosedLoopVoltage()
public void SetVelocityMeasurementPeriod(CANTalon.VelocityMeasurementPeriod period)
period - Support period enum. Curent valid values are 1,2,5,10,20,25,50, or 100ms.public void SetVelocityMeasurementWindow(int windowSize)
windowSize - Window size of rolling average.public CANTalon.VelocityMeasurementPeriod GetVelocityMeasurementPeriod()
public int GetVelocityMeasurementWindow()
public void changeMotionControlFramePeriod(int periodMs)
public void clearMotionProfileTrajectories()
public int getMotionProfileTopLevelBufferCount()
public boolean pushMotionProfileTrajectory(CANTalon.TrajectoryPoint trajPt)
Will return CTR_OKAY if trajectory point push ok. CTR_BufferFull if buffer is full due to kMotionProfileTopBufferCapacity.
trajPt - CANTalon.TrajectoryPointpublic boolean isMotionProfileTopLevelBufferFull()
public void processMotionProfileBuffer()
public void getMotionProfileStatus(CANTalon.MotionProfileStatus motionProfileStatus)
motionProfileStatus - [out] 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()
Once the Motion Profile Executer sets the hasUnderrun flag, it stays set until Robot Application clears it with this routine, which ensures Robot Application gets a chance to instrument or react. Caller could also check the isUnderrun flag which automatically clears when fault condition is removed.
public void setMotionMagicCruiseVelocity(double motMagicCruiseVeloc)
motmagicCruiseVeloc - Cruise(peak) velocity in RPM.public void setMotionMagicAcceleration(double motMagicAccel)
motMagicAccel - Accerleration in RPM per second.public double getMotionMagicCruiseVelocity()
public double getMotionMagicAcceleration()
public void setCurrentLimit(int amps)
public void EnableCurrentLimit(boolean enable)
public int GetGadgeteerStatus(GadgeteerUartClient.GadgeteerUartStatus status)
GetGadgeteerStatus in interface GadgeteerUartClientpublic java.lang.String getLastError()
public void setExpiration(double timeout)
setExpiration in interface edu.wpi.first.wpilibj.MotorSafetypublic double getExpiration()
getExpiration in interface edu.wpi.first.wpilibj.MotorSafetypublic boolean isAlive()
isAlive in interface edu.wpi.first.wpilibj.MotorSafetypublic boolean isSafetyEnabled()
isSafetyEnabled in interface edu.wpi.first.wpilibj.MotorSafetypublic void setSafetyEnabled(boolean enabled)
setSafetyEnabled in interface edu.wpi.first.wpilibj.MotorSafetypublic java.lang.String getDescription()
getDescription in interface edu.wpi.first.wpilibj.MotorSafetypublic void initTable(edu.wpi.first.wpilibj.tables.ITable subtable)
initTable in interface edu.wpi.first.wpilibj.Sendablepublic void updateTable()
updateTable in interface edu.wpi.first.wpilibj.CANSpeedControllerupdateTable in interface edu.wpi.first.wpilibj.livewindow.LiveWindowSendablepublic edu.wpi.first.wpilibj.tables.ITable getTable()
getTable in interface edu.wpi.first.wpilibj.Sendablepublic void startLiveWindowMode()
startLiveWindowMode in interface edu.wpi.first.wpilibj.livewindow.LiveWindowSendablepublic void stopLiveWindowMode()
stopLiveWindowMode in interface edu.wpi.first.wpilibj.livewindow.LiveWindowSendable