CANSparkBase

class rev.CANSparkBase

Bases: CANSparkLowLevel

class ExternalFollower

Bases: pybind11_object

property arbId
property configId
class FaultID(value: int)

Bases: pybind11_object

Members:

kBrownout

kOvercurrent

kIWDTReset

kMotorFault

kSensorFault

kStall

kEEPROMCRC

kCANTX

kCANRX

kHasReset

kDRVFault

kOtherFault

kSoftLimitFwd

kSoftLimitRev

kHardLimitFwd

kHardLimitRev

kBrownout = <FaultID.kBrownout: 0>
kCANRX = <FaultID.kCANRX: 8>
kCANTX = <FaultID.kCANTX: 7>
kDRVFault = <FaultID.kDRVFault: 10>
kEEPROMCRC = <FaultID.kEEPROMCRC: 6>
kHardLimitFwd = <FaultID.kHardLimitFwd: 14>
kHardLimitRev = <FaultID.kHardLimitRev: 15>
kHasReset = <FaultID.kHasReset: 9>
kIWDTReset = <FaultID.kIWDTReset: 2>
kMotorFault = <FaultID.kMotorFault: 3>
kOtherFault = <FaultID.kOtherFault: 11>
kOvercurrent = <FaultID.kOvercurrent: 1>
kSensorFault = <FaultID.kSensorFault: 4>
kSoftLimitFwd = <FaultID.kSoftLimitFwd: 12>
kSoftLimitRev = <FaultID.kSoftLimitRev: 13>
kStall = <FaultID.kStall: 5>
property name
property value
class IdleMode(value: int)

Bases: pybind11_object

Members:

kCoast

kBrake

kBrake = <IdleMode.kBrake: 1>
kCoast = <IdleMode.kCoast: 0>
property name
property value
class SoftLimitDirection(value: int)

Bases: pybind11_object

Members:

kForward

kReverse

kForward = <SoftLimitDirection.kForward: 0>
kReverse = <SoftLimitDirection.kReverse: 1>
property name
property value
burnFlash() rev._rev.REVLibError

Writes all settings to flash.

clearFaults() rev._rev.REVLibError

Clears all non-sticky faults.

Sticky faults must be cleared by resetting the motor controller.

disable() None

Common interface for disabling a motor.

disableVoltageCompensation() rev._rev.REVLibError

Disables the voltage compensation setting for all modes on the SPARK.

Returns:

REVLibError::kOk if successful

enableSoftLimit(direction: rev._rev.CANSparkBase.SoftLimitDirection, enable: bool) rev._rev.REVLibError

Enable soft limits

Parameters:
  • direction – the direction of motion to restrict

  • enable – set true to enable soft limits

enableVoltageCompensation(nominalVoltage: float) rev._rev.REVLibError

Sets the voltage compensation setting for all modes on the SPARK and enables voltage compensation.

Parameters:

nominalVoltage – Nominal voltage to compensate output to

Returns:

REVLibError::kOk if successful

follow(*args, **kwargs)

Overloaded function.

  1. follow(self: rev._rev.CANSparkBase, leader: rev._rev.CANSparkBase, invert: bool = False) -> rev._rev.REVLibError

Causes this controller’s output to mirror the provided leader.

Only voltage output is mirrored. Settings changed on the leader do not affect the follower.

Following anything other than a CAN-enabled SPARK is not officially supported.

Parameters:
  • leader – The motor controller to follow.

  • invert – Set the follower to output opposite of the leader

  1. follow(self: rev._rev.CANSparkBase, leader: rev._rev.CANSparkBase.ExternalFollower, deviceID: int, invert: bool = False) -> rev._rev.REVLibError

Causes this controller’s output to mirror the provided leader.

Only voltage output is mirrored. Settings changed on the leader do not affect the follower.

Following anything other than a CAN-enabled SPARK is not officially supported.

Parameters:
  • leader – The type of motor controller to follow (Talon SRX, Spark Max, etc.).

  • deviceID – The CAN ID of the device to follow.

  • invert – Set the follower to output opposite of the leader

get() float

Common interface for getting the current set speed of a speed controller.

Returns:

The current set speed. Value is between -1.0 and 1.0.

getAbsoluteEncoder(*args, **kwargs)

Overloaded function.

  1. getAbsoluteEncoder(self: rev._rev.CANSparkBase, encoderType: rev._rev.SparkAbsoluteEncoder.Type = <Type.kDutyCycle: 0>) -> rev._rev.SparkAbsoluteEncoder

Returns an object for interfacing with a connected absolute encoder.

The default encoder type is assumed to be a duty cycle sensor.

  1. getAbsoluteEncoder(self: rev._rev.CANSparkBase, encoderType: rev._rev.SparkMaxAbsoluteEncoder.Type) -> rev._rev.SparkAbsoluteEncoder

Returns an object for interfacing with a connected absolute encoder.

Deprecated:

Use GetAbsoluteEncoder(SparkAbsoluteEncoder::Type) instead

getAnalog(*args, **kwargs)

Overloaded function.

  1. getAnalog(self: rev._rev.CANSparkBase, mode: rev._rev.SparkAnalogSensor.Mode = <Mode.kAbsolute: 0>) -> rev._rev.SparkAnalogSensor

Returns an object for interfacing with a connected analog sensor. By default, the mode is set to kAbsolute, thus treating the sensor as an absolute sensor.

  1. getAnalog(self: rev._rev.CANSparkBase, mode: rev._rev.SparkMaxAnalogSensor.Mode) -> rev._rev.SparkAnalogSensor

Returns an object for interfacing with a connected analog sensor. By default, the mode is set to kAbsolute, thus treating the sensor as an absolute sensor.

Deprecated:

Use GetAnalog(SparkAnalogSensor::Mode) instead

getAppliedOutput() float

Returns motor controller’s output duty cycle.

getBusVoltage() float

Returns the voltage fed into the motor controller.

getClosedLoopRampRate() float

Get the configured closed loop ramp rate

This is the maximum rate at which the motor controller’s output is allowed to change.

Returns:

rampte rate time in seconds to go from 0 to full throttle.

getEncoder(*args, **kwargs)

Overloaded function.

  1. getEncoder(self: rev._rev.CANSparkBase) -> rev._rev.SparkRelativeEncoder

Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX or the motor interface of the SPARK Flex.

For a SPARK MAX in brushless mode, it is assumed that the default encoder type is hall effect and the counts per revolution is 42.

For a SPARK Flex in brushless mode, it is assumed that the default encoder type is quadrature and the counts per revolution is 7168.

  1. getEncoder(self: rev._rev.CANSparkBase, encoderType: rev._rev.SparkRelativeEncoder.Type, countsPerRev: int) -> rev._rev.SparkRelativeEncoder

Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX or the motor interface of the SPARK Flex.

  1. getEncoder(self: rev._rev.CANSparkBase, encoderType: rev._rev.SparkMaxRelativeEncoder.Type, countsPerRev: int) -> rev._rev.SparkRelativeEncoder

Returns an object for interfacing with the encoder connected to the encoder pins or front port of the SPARK MAX or the motor interface of the SPARK Flex.

Deprecated:

Use GetEncoder(SparkRelativeEncoder::Type, int) instead

getFault(faultID: rev._rev.CANSparkBase.FaultID) bool

Returns whether the fault with the given ID occurred.

getFaults() int

Returns fault bits.

getForwardLimitSwitch(*args, **kwargs)

Overloaded function.

  1. getForwardLimitSwitch(self: rev._rev.CANSparkBase, switchType: rev._rev.SparkLimitSwitch.Type) -> rev._rev.SparkLimitSwitch

Returns an object for interfacing with the forward limit switch connected to the appropriate pins on the data port.

This call will disable support for the alternate encoder.

Parameters:

switchType – Whether the limit switch is normally open or normally closed.

  1. getForwardLimitSwitch(self: rev._rev.CANSparkBase, switchType: rev._rev.SparkMaxLimitSwitch.Type) -> rev._rev.SparkLimitSwitch

Returns an object for interfacing with the forward limit switch connected to the appropriate pins on the data port.

This call will disable support for the alternate encoder.

Deprecated:

Use GetForwardLimitSwitch(SparkLimitSwitch::Type) instead

Parameters:

switchType – Whether the limit switch is normally open or normally closed.

getIdleMode() rev._rev.CANSparkBase.IdleMode

Gets the idle mode setting for the SPARK.

This uses the Get Parameter API and should be used infrequently. This function uses a non-blocking call and will return a cached value if the parameter is not returned by the timeout. The timeout can be changed by calling SetCANTimeout(int milliseconds)

Returns:

IdleMode Idle mode setting

getInverted() bool

Common interface for returning the inversion state of a speed controller.

This call has no effect if the controller is a follower.

Returns:

isInverted The state of inversion, true is inverted.

getLastError() rev._rev.REVLibError

All device errors are tracked on a per thread basis for all devices in that thread. This is meant to be called immediately following another call that has the possibility of throwing an error to validate if an error has occurred.

Returns:

the last error that was generated.

getMotorTemperature() float

Returns the motor temperature in Celsius.

getOpenLoopRampRate() float

Get the configured open loop ramp rate

This is the maximum rate at which the motor controller’s output is allowed to change.

Returns:

rampte rate time in seconds to go from 0 to full throttle.

getOutputCurrent() float

Returns motor controller’s output current in Amps.

getPIDController() rev._rev.SparkPIDController

Returns an object for interfacing with the integrated PID controller.

getReverseLimitSwitch(*args, **kwargs)

Overloaded function.

  1. getReverseLimitSwitch(self: rev._rev.CANSparkBase, switchType: rev._rev.SparkLimitSwitch.Type) -> rev._rev.SparkLimitSwitch

Returns an object for interfacing with the reverse limit switch connected to the appropriate pins on the data port.

This call will disable support for the alternate encoder.

Parameters:

switchType – Whether the limit switch is normally open or normally closed.

  1. getReverseLimitSwitch(self: rev._rev.CANSparkBase, switchType: rev._rev.SparkMaxLimitSwitch.Type) -> rev._rev.SparkLimitSwitch

Returns an object for interfacing with the reverse limit switch connected to the appropriate pins on the data port.

This call will disable support for the alternate encoder.

Deprecated:

Use GetReverseLimitSwitch(SparkLimitSwitch::Type) instead

Parameters:

switchType – Whether the limit switch is normally open or normally closed.

getSoftLimit(direction: rev._rev.CANSparkBase.SoftLimitDirection) float

Get the soft limit setting in the controller

Parameters:

direction – the direction of motion to restrict

Returns:

position soft limit setting of the controller

getStickyFault(faultID: rev._rev.CANSparkBase.FaultID) bool

Returns whether the sticky fault with the given ID occurred.

getStickyFaults() int

Returns sticky fault bits.

getVoltageCompensationNominalVoltage() float

Get the configured voltage compensation nominal voltage value

Returns:

The nominal voltage for voltage compensation mode.

isFollower() bool

Returns whether the controller is following another controller

Returns:

True if this device is following another controller false otherwise

isSoftLimitEnabled(direction: rev._rev.CANSparkBase.SoftLimitDirection) bool

Returns true if the soft limit is enabled.

kFollowerDisabled = <rev._rev.CANSparkBase.ExternalFollower object>
kFollowerPhoenix = <rev._rev.CANSparkBase.ExternalFollower object>
kFollowerSpark = <rev._rev.CANSparkBase.ExternalFollower object>
kFollowerSparkMax = <rev._rev.CANSparkBase.ExternalFollower object>
set(speed: float) None

Common interface for setting the speed of a speed controller.

Parameters:

speed – The speed to set. Value should be between -1.0 and 1.0.

setCANTimeout(milliseconds: int) rev._rev.REVLibError

Sets timeout for sending CAN messages. A timeout of 0 also means that error handling will be done automatically by registering calls and waiting for responses, rather than needing to call GetLastError().

Parameters:

milliseconds – The timeout in milliseconds.

setClosedLoopRampRate(rate: float) rev._rev.REVLibError

Sets the ramp rate for closed loop control modes.

This is the maximum rate at which the motor controller’s output is allowed to change.

Parameters:

rate – Time in seconds to go from 0 to full throttle.

setIdleMode(mode: rev._rev.CANSparkBase.IdleMode) rev._rev.REVLibError

Sets the idle mode setting for the SPARK.

Parameters:

mode – Idle mode (coast or brake).

setInverted(isInverted: bool) None

Common interface for inverting direction of a speed controller.

This call has no effect if the controller is a follower. To invert a follower, see the follow() method.

Parameters:

isInverted – The state of inversion, true is inverted.

setOpenLoopRampRate(rate: float) rev._rev.REVLibError

Sets the ramp rate for open loop control modes.

This is the maximum rate at which the motor controller’s output is allowed to change.

Parameters:

rate – Time in seconds to go from 0 to full throttle.

setSecondaryCurrentLimit(limit: float, limitCycles: int = 0) rev._rev.REVLibError

Sets the secondary current limit in Amps.

The motor controller will disable the output of the controller briefly if the current limit is exceeded to reduce the current. This limit is a simplified ‘on/off’ controller. This limit is enabled by default but is set higher than the default Smart Current Limit.

The time the controller is off after the current limit is reached is determined by the parameter limitCycles, which is the number of PWM cycles (20kHz). The recommended value is the default of 0 which is the minimum time and is part of a PWM cycle from when the over current is detected. This allows the controller to regulate the current close to the limit value.

The total time is set by the equation

t = (50us - t0) + 50us * limitCycles
t = total off time after over current
t0 = time from the start of the PWM cycle until over current is detected
Parameters:
  • limit – The current limit in Amps.

  • limitCycles – The number of additional PWM cycles to turn the driver off after overcurrent is detected.

setSmartCurrentLimit(*args, **kwargs)

Overloaded function.

  1. setSmartCurrentLimit(self: rev._rev.CANSparkBase, limit: int) -> rev._rev.REVLibError

Sets the current limit in Amps.

The motor controller will reduce the controller voltage output to avoid surpassing this limit. This limit is enabled by default and used for brushless only. This limit is highly recommended when using the NEO brushless motor.

The NEO Brushless Motor has a low internal resistance, which can mean large current spikes that could be enough to cause damage to the motor and controller. This current limit provides a smarter strategy to deal with high current draws and keep the motor and controller operating in a safe region.

Parameters:

limit – The current limit in Amps.

  1. setSmartCurrentLimit(self: rev._rev.CANSparkBase, stallLimit: int, freeLimit: int, limitRPM: int = 20000) -> rev._rev.REVLibError

Sets the current limit in Amps.

The motor controller will reduce the controller voltage output to avoid surpassing this limit. This limit is enabled by default and used for brushless only. This limit is highly recommended when using the NEO brushless motor.

The NEO Brushless Motor has a low internal resistance, which can mean large current spikes that could be enough to cause damage to the motor and controller. This current limit provides a smarter strategy to deal with high current draws and keep the motor and controller operating in a safe region.

The controller can also limit the current based on the RPM of the motor in a linear fashion to help with controllability in closed loop control. For a response that is linear the entire RPM range leave limit RPM at 0.

Parameters:
  • stallLimit – The current limit in Amps at 0 RPM.

  • freeLimit – The current limit at free speed (5700RPM for NEO).

  • limitRPM – RPM less than this value will be set to the stallLimit, RPM values greater than limitRPM will scale linearly to freeLimit

setSoftLimit(direction: rev._rev.CANSparkBase.SoftLimitDirection, limit: float) rev._rev.REVLibError

Set the soft limit based on position. The default unit is rotations, but will match the unit scaling set by the user.

Note that this value is not scaled internally so care must be taken to make sure these units match the desired conversion

Parameters:
  • direction – the direction of motion to restrict

  • limit – position soft limit of the controller

setVoltage(output: wpimath.units.volts) None

Sets the voltage output of the SpeedController. This is equivalent to a call to SetReference(output, CANSparkBase::ControlType::kVoltage). The behavior of this call differs slightly from the WPILib documentation for this call since the device internally sets the desired voltage (not a compensation value). That means that this can be a ‘set-and-forget’ call.

Parameters:

output – The voltage to output.

stopMotor() None

Common interface to stop the motor until Set is called again.