CANTalon

class wpilib.CANTalon(deviceNumber, controlPeriodMs=None, enablePeriodMs=None)[source]

Bases: wpilib.LiveWindowSendable, wpilib.MotorSafety

Talon SRX device as a CAN device

The TALON SRX is designed to instrument all runtime signals periodically. The default periods are chosen to support 16 TALONs with 10ms update rate for control (throttle or setpoint). However these can be overridden with setStatusFrameRate().

Likewise most control signals are sent periodically using the fire-and-forget CAN API.

Signals that are not available in an unsolicited fashion are the Close Loop gains. For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application. These parameters are saved to flash so once they are loaded in the TALON, they will persist through power cycles and mode changes.

For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from and the ProfileSlotSelect is periodically sent in the 10 ms control frame.

For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters. Most likely they will only need to set them in a periodic fashion as a function of what motion the application is attempting. If this API is used, be mindful of the CAN utilization reported in the driver station.

If calling application has used the config routines to configure the selected feedback sensor, then all positions are measured in floating point precision rotations. All sensor velocities are specified in floating point precision RPM.

HOWEVER, if calling application has not called the config routine for selected feedback sensor, then all getters/setters for position/velocity use the native engineering units of the Talon SRX firm (just like in 2015). Signals explained below.

Encoder position is measured in encoder edges. Every edge is counted (similar to roboRIO 4X mode). Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V). Use setFeedbackDevice() to select which sensor type you need. Once you do that you can use getSensorPosition() and getSensorVelocity(). These signals are updated on CANBus every 20ms (by default). If a relative sensor is selected, you can zero (or change the current value) using setSensorPosition().

Analog Input and quadrature position (and velocity) are also explicitly reported in getEncPosition(), getEncVelocity(), getAnalogInPosition(), getAnalogInRaw(), getAnalogInVelocity(). These signals are available all the time, regardless of what sensor is selected at a rate of 100ms. This allows easy instrumentation for “in the pits” checking of all sensors regardless of modeselect. The 100ms rate is overridable for teams who want to acquire sensor data for processing, not just instrumentation. Or just select the sensor using setFeedbackDevice() to get it at 20ms.

Velocity is in position ticks / 100ms.

All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward). This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).

When in (default) PercentVBus mode, set() and get() are automatically scaled to a -1.0 to +1.0 range to match other motor controllers.

Pos and velocity close loops are calc’d as:

err = target - posOrVel
iErr += err
if IZone != 0 and abs(err) > IZone:
    ClearIaccum()
output = P * err + I * iErr + D * dErr + F * target
dErr = err - lastErr

P, I, and D gains are always positive. F can be negative.

Motor direction can be reversed using reverseOutput() if sensor and motor are out of phase. Similarly feedback sensor can also be reversed (multiplied by -1) using reverseSensor() if you prefer the sensor to be inverted.

P gain is specified in throttle per error tick. For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1 ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023) for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor. Close loop and integral accumulator runs every 1ms.

D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023) per change of 1 unit (ADC or encoder) per ms.

I Zone is specified in the same units as sensor position (ADC units or quadrature edges). If pos/vel error is outside of this value, the integrated error will auto-clear:

if IZone != 0 and abs(err) > IZone:
    ClearIaccum()

This is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.

CloseLoopRampRate is in throttle units per 1ms. Set to zero to disable ramping. Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.

class ControlMode[source]

Bases: object

Current = 3
Disabled = 15
Follower = 5
MotionProfile = 6
PercentVbus = 0
Position = 1
Speed = 2
Voltage = 4
class CANTalon.FeedbackDevice[source]

Bases: object

AnalogEncoder = 3
AnalogPot = 2
CtreMagEncoder_Absolute = 7
CtreMagEncoder_Relative = 6
EncFalling = 5
EncRising = 4
PulseWidth = 8
QuadEncoder = 0
class CANTalon.FeedbackDeviceStatus[source]

Bases: object

NotPresent = 2
Present = 1
Unknown = 0
class CANTalon.MotionProfileStatus[source]

Bases: object

This is simply a data transfer object

activePoint = None

(TrajectoryPoint) The number of points in the low level Talon buffer.

activePointValid

(bool) True if the active trajectory point has not empty, false otherwise. The members in activePoint are only valid if this signal is set.

btmBufferCnt = 0

(int) The number of points in the low level Talon buffer.

hasUnderrun

(bool) Set if isUnderrun ever gets set. Only is cleared by clearMotionProfileHasUnderrun() to ensure robot logic can react or instrument it.

See also

clearMotionProfileHasUnderrun()

isUnderrun

(bool) This is set if Talon needs to shift a point from its buffer into the active trajectory point however the buffer is empty. This gets cleared automatically when is resolved.

outputEnable = 0

(SetValueMotionProfile) The current output mode of the motion profile executer (disabled, enabled, or hold). When changing the set() value in MP mode, it’s important to check this signal to confirm the change takes effect before interacting with the top buffer.

topBufferCnt = 0

(int) The number of points in the top trajectory buffer.

topBufferRem = 0

(int) The available empty slots in the trajectory buffer.

The robot API holds a “top buffer” of trajectory points, so your applicaion can dump several points at once. The API will then stream them into the Talon’s low-level buffer, allowing the Talon to act on them.

class CANTalon.PIDSourceType

Bases: object

A description for the type of output value to provide to a PIDController

kDisplacement = 0
kRate = 1
class CANTalon.SetValueMotionProfile[source]

Bases: object

Enumerated types for Motion Control Set Values.

When in Motion Profile control mode, these constants are paseed into set() to manipulate the motion profile executer.

When changing modes, be sure to read the value back using getMotionProfileStatus() to ensure changes in output take effect before performing buffering actions.

Disable will signal Talon to put motor output into neutral drive.

Talon will stop processing motion profile points. This means the buffer is effectively disconnected from the executer, allowing the robot to gracefully clear and push new traj points. isUnderrun will get cleared. The active trajectory is also cleared.

Enable will signal Talon to pop a trajectory point from it’s buffer and process it. If the active trajectory is empty, Talon will shift in the next point. If the active traj is empty, and so is the buffer, the motor drive is neutral and isUnderrun is set. When active traj times out, and buffer has at least one point, Talon shifts in next one, and isUnderrun is cleared. When active traj times out, and buffer is empty, Talon keeps processing active traj and sets IsUnderrun.

Hold will signal Talon keep processing the active trajectory indefinitely. If the active traj is cleared, Talon will neutral motor drive. Otherwise Talon will keep processing the active traj but it will not shift in points from the buffer. This means the buffer is effectively disconnected from the executer, allowing the robot to gracefully clear and push new traj points. isUnderrun is set if active traj is empty, otherwise it is cleared. isLast signal is also cleared.

Typical workflow:

  • set(Disable),
  • Confirm Disable takes effect,
  • clear buffer and push buffer points,
  • set(Enable) when enough points have been pushed to ensure no underruns,
  • wait for MP to finish or decide abort,
  • If MP finished gracefully set(Hold) to hold position servo and disconnect buffer,
  • If MP is being aborted set(Disable) to neutral the motor and disconnect buffer,
  • Confirm mode takes effect,
  • clear buffer and push buffer points, and rinse-repeat.
Disable = 0
Enable = 1
Hold = 2
class CANTalon.StatusFrameRate[source]

Bases: object

enumerated types for frame rate ms

AnalogTempVbat = 3
Feedback = 1
General = 0
PulseWidth = 4
QuadEncoder = 2
class CANTalon.TrajectoryPoint[source]

Bases: object

This is a data transfer object

isLastPoint = False

(bool) Set to true to signal Talon that this is the final point, so do not attempt to pop another trajectory point from out of the Talon buffer. Instead continue processing this way point. Typically the velocity member variable should be zero so that the motor doesn’t spin indefinitely.

position = 0

(double) the position to servo to

profileSlotSelect = 0

(int) Which slot to get PIDF gains. PID is used for position servo. F is used as the Kv constant for velocity feed-forward. Typically this is hardcoded to the a particular slot, but you are free gain schedule if need be.

timeDurMs = 0

(int) Time in milliseconds to process this point. Value should be between 1ms and 255ms. If value is zero then Talon will default to 1ms. If value exceeds 255ms API will cap it.

velocity = 0

(double) The velocity to feed-forward

velocityOnly = False

Set to true to only perform the velocity feed-forward and not perform position servo. This is useful when learning how the position servo changes the motor response. The same could be accomplish by clearing the PID gains, however this is synchronous the streaming, and doesn’t require restoing gains when finished.

Additionaly setting this basically gives you direct control of the motor output since motor output = targetVelocity X Kv, where Kv is our Fgain. This means you can also scheduling straight-throttle curves without relying on a sensor.

zeroPos = False

(bool) Set to true to signal Talon to zero the selected sensor. When generating MPs, one simple method is to make the first target position zero, and the final target position the target distance from the current position. Then when you fire the MP, the current position gets set to zero. If this is the intent, you can set zeroPos on the first trajectory point.

Otherwise you can leave this false for all points, and offset the positions of all trajectory points so they are correct.

CANTalon.changeControlMode(controlMode)[source]
CANTalon.changeMotionControlFramePeriod(periodMs)[source]

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. Ideally the period should be no more than half the period of a trajectory point.

CANTalon.clearIaccum()[source]

Clear the accumulator for I gain.

CANTalon.clearMotionProfileHasUnderrun()[source]

Clear the hasUnderrun flag in Talon’s Motion Profile Executer when MPE is ready for another point, but the low level buffer is empty.

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.

CANTalon.clearMotionProfileTrajectories()[source]

Clear the buffered motion profile in both Talon RAM (bottom), and in the API (top). Be sure to check getMotionProfileStatus() to know when the buffer is actually cleared.

CANTalon.clearStickyFaults()[source]
CANTalon.configEncoderCodesPerRev(codesPerRev)[source]

Configure how many codes per revolution are generated by your encoder.

Parameters:codesPerRev – The number of counts per revolution.
CANTalon.configFwdLimitSwitchNormallyOpen(normallyOpen)[source]

Configure the fwd limit switch to be normally open or normally closed. Talon will disable momentarilly if the Talon’s current setting is dissimilar to the caller’s requested setting.

Since Talon saves setting to flash this should only affect a given Talon initially during robot install.

Parameters:normallyOpen – True for normally open. False for normally closed.
CANTalon.configMaxOutputVoltage(voltage)[source]

Configure the maximum voltage that the Jaguar will ever output.

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.

Parameters:voltage – The maximum voltage output by the Jaguar.
CANTalon.configNominalOutputVoltage(forwardVoltage, reverseVoltage)[source]
CANTalon.configPeakOutputVoltage(forwardVoltage, reverseVoltage)[source]
CANTalon.configPotentiometerTurns(turns)[source]

Configure the number of turns on the potentiometer.

Parameters:turns – The number of turns of the potentiometer.
CANTalon.configRevLimitSwitchNormallyOpen(normallyOpen)[source]
  • Configure the rev limit switch to be normally open or normally closed.
  • Talon will disable momentarilly if the Talon’s current setting
  • is dissimilar to the caller’s requested setting.
  • Since Talon saves setting to flash this should only affect
  • a given Talon initially during robot install.
  • @param normallyOpen true for normally open. false for normally closed.
CANTalon.disable()[source]
CANTalon.disableControl()[source]
CANTalon.enable()[source]
CANTalon.enableBrakeMode(brake)[source]
CANTalon.enableControl()[source]
CANTalon.enableForwardSoftLimit(enable)[source]
CANTalon.enableLimitSwitch(forward, reverse)[source]
CANTalon.enableReverseSoftLimit(enable)[source]
CANTalon.enableZeroSensorPositionOnIndex(enable, risingEdge)[source]

Enables Talon SRX to automatically zero the Sensor Position whenever an edge is detected on the index signal.

Parameters:
  • enable (bool) – boolean input, pass true to enable feature or false to disable.
  • risingEdge (bool) –

    boolean input, pass true to clear the position on rising edge,

    pass false to clear the position on falling edge.

CANTalon.free()[source]
CANTalon.get()[source]

Gets the current status of the Talon (usually a sensor value).

In Current mode: returns output current.

In Speed mode: returns current speed.

In Position mode: returns current sensor position.

In Throttle and Follower modes: returns current applied throttle.

Returns:The current sensor value of the Talon.
CANTalon.getAnalogInPosition()[source]

Get the current analog in position, regardless of whether it is the current feedback device.

Returns:The 24bit analog position. 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).
CANTalon.getAnalogInRaw()[source]

Get the current analog in position, regardless of whether it is the current feedback device. :returns: The ADC (0 - 1023) on analog pin of the Talon.

CANTalon.getAnalogInVelocity()[source]

Get the current encoder velocity, regardless of whether it is the current feedback device.

Returns:The current speed of the analog in device.
CANTalon.getBrakeEnableDuringNeutral()[source]

Returns True if break is enabled during neutral. False if coast.

CANTalon.getBusVoltage()[source]
Returns:The voltage at the battery terminals of the Talon, in Volts.
CANTalon.getCloseLoopRampRate()[source]

Get the closed loop ramp rate for the current profile.

Limits the rate at which the throttle will change. Only affects position and speed closed loop modes.

Returns:rampRate Maximum change in voltage, in volts / sec.
See:#setProfile For selecting a certain profile.

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getClosedLoopError()[source]

Get the current difference between the setpoint and the sensor value.

Returns:The error, in whatever units are appropriate.
CANTalon.getControlMode()[source]
CANTalon.getD()[source]

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getDescription()[source]
CANTalon.getDeviceID()[source]
CANTalon.getEncPosition()[source]

Get the current encoder position, regardless of whether it is the current feedback device.

Returns:The current position of the encoder.
CANTalon.getEncVelocity()[source]

Get the current encoder velocity, regardless of whether it is the current feedback device.

Returns:The current speed of the encoder.
CANTalon.getError()[source]

Returns the difference between the setpoint and the current position.

Returns:The error in units corresponding to whichever mode we are in.

See also

set() for a detailed description of the various units.

CANTalon.getF()[source]

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getFaultForLim()[source]
CANTalon.getFaultForSoftLim()[source]
CANTalon.getFaultHardwareFailure()[source]
CANTalon.getFaultOverTemp()[source]
CANTalon.getFaultRevLim()[source]
CANTalon.getFaultRevSoftLim()[source]
CANTalon.getFaultUnderVoltage()[source]
CANTalon.getFirmwareVersion()[source]
Returns:The version of the firmware running on the Talon

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getForwardSoftLimit()[source]
CANTalon.getI()[source]

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getIZone()[source]

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getIaccum()[source]

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getInverted()[source]

Common interface for the inverting direction of a speed controller.

Returns:The state of inversion (True is inverted).
CANTalon.getMotionProfileStatus(motionProfileStatus)[source]

Retrieve all Motion Profile status information.

Since this all comes from one CAN frame, its ideal to have one routine to retrieve the frame once and decode everything.

Parameters:motionProfileStatus (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.
CANTalon.getMotionProfileTopLevelBufferCount()[source]

Retrieve just the buffer count for the api-level (top) buffer. This routine performs no CAN or data structure lookups, so its fast and ideal if caller needs to quickly poll the progress of trajectory points being emptied into Talon’s RAM. Otherwise just use getMotionProfileStatus().

Returns:number of trajectory points in the top buffer.
CANTalon.getNumberOfQuadIdxRises()[source]

Get the number of of rising edges seen on the index pin.

Returns:number of rising edges on idx pin.
CANTalon.getOutputCurrent()[source]

Returns the current going through the Talon, in Amperes.

CANTalon.getOutputVoltage()[source]
Returns:The voltage being output by the Talon, in Volts.
CANTalon.getP()[source]

Get the current proportional constant.

Returns:double proportional constant for current profile.

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getPIDSourceType()[source]
CANTalon.getParameter(param)[source]

General get frame. Since the parameter is a general integral type, this can be used for testing future features.

Warning

Calls Timer.delay(kDelayForSolicitedSignals)

CANTalon.getPinStateQuadA()[source]
Returns:IO level of QUADA pin.
CANTalon.getPinStateQuadB()[source]
Returns:IO level of QUADB pin.
CANTalon.getPinStateQuadIdx()[source]
Returns:IO level of QUAD Index pin.
CANTalon.getPosition()[source]
Returns:The position of the sensor currently providing feedback. 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. When using quadrature, each unit is a quadrature edge (4X) mode.
CANTalon.getPulseWidthPosition()[source]
CANTalon.getPulseWidthRiseToFallUs()[source]
CANTalon.getPulseWidthRiseToRiseUs()[source]
CANTalon.getPulseWidthVelocity()[source]
CANTalon.getReverseSoftLimit()[source]
CANTalon.getSetpoint()[source]
Returns:The latest value set using set().
CANTalon.getSpeed()[source]
Returns:The speed of the sensor currently providing feedback.

The speed units will be in the sensor’s native ticks per 100ms.

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.

CANTalon.getStickyFaultForLim()[source]
CANTalon.getStickyFaultForSoftLim()[source]
CANTalon.getStickyFaultOverTemp()[source]
CANTalon.getStickyFaultRevLim()[source]
CANTalon.getStickyFaultRevSoftLim()[source]
CANTalon.getStickyFaultUnderVoltage()[source]
CANTalon.getTemp()

Returns temperature of Talon, in degrees Celsius.

CANTalon.getTemperature()[source]

Returns temperature of Talon, in degrees Celsius.

CANTalon.handle
CANTalon.isControlEnabled()[source]
CANTalon.isEnabled()[source]

Return true if Talon is enabled.

Returns:true if the Talon is enabled and may be applying power to the motor
CANTalon.isForwardSoftLimitEnabled()[source]
CANTalon.isFwdLimitSwitchClosed()[source]

Returns True if limit switch is closed. False if open.

CANTalon.isMotionProfileTopLevelBufferFull()[source]
Returns:true if api-level (top) buffer is full.
CANTalon.isRevLimitSwitchClosed()[source]

Returns True if limit switch is closed. False if open.

CANTalon.isReverseSoftLimitEnabled()[source]
CANTalon.isSensorPresent(feedbackDevice)[source]
Parameters:feedbackDevice – which feedback sensor to check it if is connected.
Returns:status of caller’s specified sensor type.
CANTalon.kDelayForSolicitedSignals = 0.004
CANTalon.kMinutesPer100msUnit = 0.0016666666666666668

Number of minutes per 100ms unit. Useful for scaling velocities measured by Talon’s 100ms timebase to rotations per minute.

CANTalon.kNativeAdcUnitsPerRotation = 1024

Number of adc engineering units per 0 to 3.3V sweep. This is necessary for scaling Analog Position in rotations/RPM.

CANTalon.kNativePwdUnitsPerRotation = 4096.0

Number of pulse width engineering units per full rotation. This is necessary for scaling Pulse Width Decoded Position in rotations/RPM.

CANTalon.pidGet()[source]
CANTalon.pidWrite(output)[source]
CANTalon.processMotionProfileBuffer()[source]

This must be called periodically to funnel the trajectory points from the API’s top level buffer to the Talon’s bottom level buffer. Recommendation is to call this twice as fast as the executation rate of the motion profile. So if MP is running with 20ms trajectory points, try calling this routine every 10ms. All motion profile functions are thread-safe through the use of a mutex, so there is no harm in having the caller utilize threading.

CANTalon.pushMotionProfileTrajectory(trajPt)[source]

Push another trajectory point into the top level buffer (which is emptied into the Talon’s bottom buffer as room allows).

Parameters:
  • 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.
Returns:

True if trajectory point push ok. False if buffer is full due to kMotionProfileTopBufferCapacity.

CANTalon.reset()[source]

Resets the accumulated integral error and disables the controller.

The only difference between this and {@link 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.

CANTalon.reverseOutput(flip)[source]

Flips the sign (multiplies by negative one) the throttle values going into the motor on the talon in closed loop modes.

Parameters:flip – True if motor output should be flipped; False if not.
CANTalon.reverseSensor(flip)[source]

Flips the sign (multiplies by negative one) the sensor values going into the talon.

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.
Parameters:flip – True if sensor input should be flipped; False if not.
CANTalon.set(outputValue, syncGroup=0)[source]

Sets the appropriate output on the talon, depending on the mode.

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.
Parameters:outputValue – The setpoint value, as described above.
CANTalon.setAllowableClosedLoopErr(allowableCloseLoopError)[source]

Set the allowable closed loop error.

Parameters:allowableCloseLoopError – allowable closed loop error for selected profile. mA for Curent closed loop. Talon Native Units for position and velocity.
CANTalon.setAnalogPosition(newPosition)[source]
CANTalon.setCloseLoopRampRate(rampRate)[source]

Set the closed loop ramp rate for the current profile.

Limits the rate at which the throttle will change. Only affects position and speed closed loop modes.

Parameters:rampRate – Maximum change in voltage, in volts / sec.
See:setProfile() For selecting a certain profile.
CANTalon.setControlMode(controlMode)[source]
CANTalon.setD(d)[source]

Set the derivative constant of the currently selected profile.

Parameters:d – Derivative constant for the currently selected PID profile.
See:setProfile() For selecting a certain profile.
CANTalon.setEncPosition(newPosition)[source]
CANTalon.setF(f)[source]

Set the feedforward value of the currently selected profile.

Parameters:f – Feedforward constant for the currently selected PID profile.
See:setProfile() For selecting a certain profile.
CANTalon.setFeedbackDevice(device)[source]
CANTalon.setForwardSoftLimit(forwardLimit)[source]
CANTalon.setI(i)[source]

Set the integration constant of the currently selected profile.

Parameters:i – Integration constant for the currently selected PID profile.
See:setProfile() For selecting a certain profile.
CANTalon.setIZone(izone)[source]

Set the integration zone of the current Closed Loop profile.

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.

Parameters:izone – Width of the integration zone.
See:setProfile() For selecting a certain profile.
CANTalon.setInverted(isInverted)[source]

Inverts the direction of the motor’s rotation. Only works in PercentVbus mode.

Parameters:isInverted – The state of inversion (True is inverted).
CANTalon.setP(p)[source]

Set the proportional value of the currently selected profile.

Parameters:p – Proportional constant for the currently selected PID profile.
See:setProfile() For selecting a certain profile.
CANTalon.setPID(p, i, d, f=0, izone=0, closeLoopRampRate=0, profile=None)[source]

Sets control values for closed loop control.

Parameters:
  • 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().
CANTalon.setPIDSourceType(pidSource)[source]
CANTalon.setParameter(param, value)[source]

General set frame. Since the parameter is a general integral type, this can be used for testing future features.

CANTalon.setPosition(pos)[source]
CANTalon.setProfile(profile)[source]

Select which closed loop profile to use, and uses whatever PIDF gains and the such that are already there.

Parameters:profile (int) – Selected profile (0 or 1)
CANTalon.setPulseWidthPosition(newPosition)[source]
CANTalon.setReverseSoftLimit(reverseLimit)[source]
CANTalon.setSetpoint(setpoint)[source]

Calls set()

CANTalon.setStatusFrameRateMs(stateFrame, periodMs)[source]

Change the periodMs of a TALON’s status frame. See StatusFrameRate enum for what’s available.

CANTalon.setVoltageCompensationRampRate(rampRate)[source]
CANTalon.setVoltageRampRate(rampRate)[source]

Set the voltage ramp rate for the current profile.

Limits the rate at which the throttle will change. Affects all modes.

Parameters:rampRate – Maximum change in voltage, in volts / sec.
CANTalon.stopMotor()[source]

Common interface for stopping a motor.