REVLib - C++
rev::CANSparkBase Class Referenceabstract

#include <CANSparkBase.h>

Inherits rev::CANSparkLowLevel.

Inherited by rev::CANSparkFlex, and rev::CANSparkMax.

Classes

struct  ExternalFollower
 

Public Types

enum class  IdleMode { kCoast = 0 , kBrake = 1 }
 
enum class  InputMode { kPWM = 0 , kCAN = 1 }
 
enum class  SoftLimitDirection { kForward , kReverse }
 
enum class  FaultID {
  kBrownout = 0 , kOvercurrent = 1 , kIWDTReset = 2 , kMotorFault = 3 ,
  kSensorFault = 4 , kStall = 5 , kEEPROMCRC = 6 , kCANTX = 7 ,
  kCANRX = 8 , kHasReset = 9 , kDRVFault = 10 , kOtherFault = 11 ,
  kSoftLimitFwd = 12 , kSoftLimitRev = 13 , kHardLimitFwd = 14 , kHardLimitRev = 15
}
 
- Public Types inherited from rev::CANSparkLowLevel
enum class  MotorType { kBrushed = 0 , kBrushless = 1 }
 
enum class  ControlType {
  kDutyCycle = 0 , kVelocity = 1 , kVoltage = 2 , kPosition = 3 ,
  kSmartMotion = 4 , kCurrent = 5 , kSmartVelocity = 6
}
 
enum class  ParameterStatus {
  kOK = 0 , kInvalidID = 1 , kMismatchType = 2 , kAccessMode = 3 ,
  kInvalid = 4 , kNotImplementedDeprecated = 5
}
 
enum class  PeriodicFrame {
  kStatus0 = 0 , kStatus1 = 1 , kStatus2 = 2 , kStatus3 = 3 ,
  kStatus4 = 4 , kStatus5 = 5 , kStatus6 = 6 , kStatus7 = 7
}
 
enum class  TelemetryID {
  kBusVoltage = 0 , kOutputCurrent , kVelocity , kPosition ,
  kIAccum , kAppliedOutput , kMotorTemp , kFaults ,
  kStickyFaults , kAnalogVoltage , kAnalogPosition , kAnalogVelocity ,
  kAltEncPosition , kAltEncVelocity , kTotalStreams
}
 
enum class  SparkModel { kSparkMax = 0 , kSparkFlex = 1 , kUnknown = 255 }
 

Public Member Functions

 ~CANSparkBase () override=default
 
void Set (double speed) override
 
void SetVoltage (units::volt_t output) override
 
double Get () const override
 
void SetInverted (bool isInverted) override
 
bool GetInverted () const override
 
void Disable () override
 
void StopMotor () override
 
virtual SparkRelativeEncoder GetEncoder ()=0
 
SparkRelativeEncoder GetEncoder (SparkRelativeEncoder::Type encoderType, int countsPerRev)
 
SparkRelativeEncoder GetEncoder (SparkMaxRelativeEncoder::Type encoderType, int countsPerRev)
 
SparkRelativeEncoder GetEncoder (CANEncoder::EncoderType encoderType, int countsPerRev)
 
SparkAnalogSensor GetAnalog (SparkAnalogSensor::Mode mode=SparkAnalogSensor::Mode::kAbsolute)
 
SparkAnalogSensor GetAnalog (SparkMaxAnalogSensor::Mode mode)
 
SparkAnalogSensor GetAnalog (CANAnalog::AnalogMode mode)
 
SparkAbsoluteEncoder GetAbsoluteEncoder (SparkAbsoluteEncoder::Type encoderType=SparkAbsoluteEncoder::Type::kDutyCycle)
 
SparkAbsoluteEncoder GetAbsoluteEncoder (SparkMaxAbsoluteEncoder::Type encoderType)
 
SparkPIDController GetPIDController ()
 
SparkLimitSwitch GetForwardLimitSwitch (SparkLimitSwitch::Type switchType)
 
SparkLimitSwitch GetForwardLimitSwitch (SparkMaxLimitSwitch::Type switchType)
 
SparkLimitSwitch GetForwardLimitSwitch (CANDigitalInput::LimitSwitchPolarity polarity)
 
SparkLimitSwitch GetReverseLimitSwitch (SparkLimitSwitch::Type switchType)
 
SparkLimitSwitch GetReverseLimitSwitch (SparkMaxLimitSwitch::Type switchType)
 
SparkLimitSwitch GetReverseLimitSwitch (CANDigitalInput::LimitSwitchPolarity polarity)
 
REVLibError SetSmartCurrentLimit (unsigned int limit)
 
REVLibError SetSmartCurrentLimit (unsigned int stallLimit, unsigned int freeLimit, unsigned int limitRPM=20000)
 
REVLibError SetSecondaryCurrentLimit (double limit, int limitCycles=0)
 
REVLibError SetIdleMode (IdleMode mode)
 
IdleMode GetIdleMode ()
 
REVLibError EnableVoltageCompensation (double nominalVoltage)
 
REVLibError DisableVoltageCompensation ()
 
double GetVoltageCompensationNominalVoltage ()
 
REVLibError SetOpenLoopRampRate (double rate)
 
REVLibError SetClosedLoopRampRate (double rate)
 
double GetOpenLoopRampRate ()
 
double GetClosedLoopRampRate ()
 
REVLibError Follow (const CANSparkBase &leader, bool invert=false)
 
REVLibError Follow (ExternalFollower leader, int deviceID, bool invert=false)
 
bool IsFollower ()
 
uint16_t GetFaults ()
 
uint16_t GetStickyFaults ()
 
bool GetFault (FaultID faultID) const
 
bool GetStickyFault (FaultID faultID) const
 
double GetBusVoltage ()
 
double GetAppliedOutput ()
 
double GetOutputCurrent ()
 
double GetMotorTemperature ()
 
REVLibError ClearFaults ()
 
REVLibError BurnFlash ()
 
REVLibError SetCANTimeout (int milliseconds)
 
REVLibError EnableSoftLimit (SoftLimitDirection direction, bool enable)
 
bool IsSoftLimitEnabled (SoftLimitDirection direction)
 
REVLibError SetSoftLimit (SoftLimitDirection direction, double limit)
 
double GetSoftLimit (SoftLimitDirection direction)
 
REVLibError GetLastError ()
 
- Public Member Functions inherited from rev::CANSparkLowLevel
virtual ~CANSparkLowLevel ()
 
uint32_t GetFirmwareVersion ()
 
uint32_t GetFirmwareVersion (bool &isDebugBuild)
 
std::string GetFirmwareString ()
 
std::vector< uint8_t > GetSerialNumber ()
 
int GetDeviceId () const
 
MotorType GetInitialMotorType ()
 
MotorType GetMotorType ()
 
REVLibError SetPeriodicFramePeriod (PeriodicFrame frame, int periodMs)
 
REVLibError SetPeriodicFramePeriod (CANSparkMaxLowLevel::PeriodicFrame frame, int periodMs)
 
void SetPeriodicFrameTimeout (int timeoutMs)
 
void SetCANMaxRetries (int numRetries)
 
void SetControlFramePeriodMs (int periodMs)
 
REVLibError RestoreFactoryDefaults (bool persist=false)
 

Static Public Attributes

static constexpr ExternalFollower kFollowerDisabled {0, 0}
 
static constexpr ExternalFollower kFollowerSparkMax {0x2051800, 26}
 
static constexpr ExternalFollower kFollowerSpark {0x2051800, 26}
 
static constexpr ExternalFollower kFollowerPhoenix {0x2040080, 27}
 
- Static Public Attributes inherited from rev::CANSparkLowLevel
static const uint8_t kAPIMajorVersion = c_SparkMax_kAPIMajorVersion
 
static const uint8_t kAPIMinorVersion = c_SparkMax_kAPIMinorVersion
 
static const uint8_t kAPIBuildVersion = c_SparkMax_kAPIBuildVersion
 
static const uint32_t kAPIVersion = c_SparkMax_kAPIVersion
 

Protected Member Functions

void attemptToSetDataportConfigOrThrow (c_SparkMax_DataPortConfig config, std::string errorText)
 
- Protected Member Functions inherited from rev::CANSparkLowLevel
PeriodicStatus0 GetPeriodicStatus0 ()
 
PeriodicStatus1 GetPeriodicStatus1 ()
 
PeriodicStatus2 GetPeriodicStatus2 ()
 
REVLibError SetFollow (FollowConfig config)
 
REVLibError SetpointCommand (double value, CANSparkLowLevel::ControlType ctrl=ControlType::kDutyCycle, int pidSlot=0, double arbFeedforward=0, int arbFFUnits=0)
 
float GetSafeFloat (float f)
 

Friends

class CANSparkMax
 
class CANSparkFlex
 
class SparkMaxLimitSwitch
 
class SparkMaxRelativeEncoder
 
class SparkMaxAlternateEncoder
 
class SparkMaxAbsoluteEncoder
 
class ::ConfigBase
 

Additional Inherited Members

- Static Public Member Functions inherited from rev::CANSparkLowLevel
static void EnableExternalUSBControl (bool enable)
 
static void SetEnable (bool enable)
 
- Protected Types inherited from rev::CANSparkLowLevel
enum class  FeedbackSensorType {
  kNoSensor = 0 , kHallSensor = 1 , kQuadrature = 2 , kSensorless = 3 ,
  kAnalog = 4 , kAltQuadrature = 5 , kDutyCycleSensor = 6
}
 
- Protected Attributes inherited from rev::CANSparkLowLevel
MotorType m_motorType
 
SparkModel m_expectedSparkModel
 
void * m_sparkMaxHandle
 

Member Enumeration Documentation

◆ IdleMode

enum class rev::CANSparkBase::IdleMode
strong
Enumerator
kCoast 
kBrake 

◆ InputMode

enum class rev::CANSparkBase::InputMode
strong
Deprecated:
You don't need this
Enumerator
kPWM 
kCAN 

◆ SoftLimitDirection

Enumerator
kForward 
kReverse 

◆ FaultID

enum class rev::CANSparkBase::FaultID
strong
Enumerator
kBrownout 
kOvercurrent 
kIWDTReset 
kMotorFault 
kSensorFault 
kStall 
kEEPROMCRC 
kCANTX 
kCANRX 
kHasReset 
kDRVFault 
kOtherFault 
kSoftLimitFwd 
kSoftLimitRev 
kHardLimitFwd 
kHardLimitRev 

Constructor & Destructor Documentation

◆ ~CANSparkBase()

rev::CANSparkBase::~CANSparkBase ( )
overridedefault

Closes the SPARK motor controller

Member Function Documentation

◆ Set()

void CANSparkBase::Set ( double  speed)
override

Common interface for setting the speed of a speed controller.

Parameters
speedThe speed to set. Value should be between -1.0 and 1.0.

◆ SetVoltage()

void CANSparkBase::SetVoltage ( units::volt_t  output)
override

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
outputThe voltage to output.

◆ Get()

double CANSparkBase::Get ( ) const
override

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.

◆ SetInverted()

void CANSparkBase::SetInverted ( bool  isInverted)
override

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
isInvertedThe state of inversion, true is inverted.

◆ GetInverted()

bool CANSparkBase::GetInverted ( ) const
override

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.

◆ Disable()

void CANSparkBase::Disable ( )
override

Common interface for disabling a motor.

◆ StopMotor()

void CANSparkBase::StopMotor ( )
override

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

◆ GetEncoder() [1/4]

virtual SparkRelativeEncoder rev::CANSparkBase::GetEncoder ( )
pure virtual

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.

Implemented in rev::CANSparkFlex, rev::CANSparkMax, rev::CANSparkFlex, and rev::CANSparkMax.

◆ GetEncoder() [2/4]

SparkRelativeEncoder CANSparkBase::GetEncoder ( SparkRelativeEncoder::Type  encoderType,
int  countsPerRev 
)

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.

◆ GetEncoder() [3/4]

SparkRelativeEncoder CANSparkBase::GetEncoder ( SparkMaxRelativeEncoder::Type  encoderType,
int  countsPerRev 
)

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

◆ GetEncoder() [4/4]

SparkRelativeEncoder CANSparkBase::GetEncoder ( CANEncoder::EncoderType  encoderType,
int  countsPerRev 
)

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 CANSparkBase::GetEncoder(SparkMaxRelativeEncoder::Type, int) instead

◆ GetAnalog() [1/3]

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.

◆ GetAnalog() [2/3]

SparkAnalogSensor CANSparkBase::GetAnalog ( SparkMaxAnalogSensor::Mode  mode)

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

◆ GetAnalog() [3/3]

SparkAnalogSensor CANSparkBase::GetAnalog ( CANAnalog::AnalogMode  mode)

Returns an object for interfacing with a connected analog sensor.

Deprecated:
Use GetAnalog(SparkMaxAnalogSensor::Mode) instead

◆ GetAbsoluteEncoder() [1/2]

SparkAbsoluteEncoder CANSparkBase::GetAbsoluteEncoder ( SparkAbsoluteEncoder::Type  encoderType = SparkAbsoluteEncoder::Type::kDutyCycle)

Returns an object for interfacing with a connected absolute encoder.

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

◆ GetAbsoluteEncoder() [2/2]

SparkAbsoluteEncoder CANSparkBase::GetAbsoluteEncoder ( SparkMaxAbsoluteEncoder::Type  encoderType)

Returns an object for interfacing with a connected absolute encoder.

Deprecated:
Use GetAbsoluteEncoder(SparkAbsoluteEncoder::Type) instead

◆ GetPIDController()

SparkPIDController CANSparkBase::GetPIDController ( )

Returns an object for interfacing with the integrated PID controller.

◆ GetForwardLimitSwitch() [1/3]

SparkLimitSwitch CANSparkBase::GetForwardLimitSwitch ( SparkLimitSwitch::Type  switchType)

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
switchTypeWhether the limit switch is normally open or normally closed.

◆ GetForwardLimitSwitch() [2/3]

SparkLimitSwitch CANSparkBase::GetForwardLimitSwitch ( SparkMaxLimitSwitch::Type  switchType)

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
switchTypeWhether the limit switch is normally open or normally closed.
Deprecated:
Use GetForwardLimitSwitch(SparkLimitSwitch::Type) instead

◆ GetForwardLimitSwitch() [3/3]

SparkLimitSwitch CANSparkBase::GetForwardLimitSwitch ( CANDigitalInput::LimitSwitchPolarity  polarity)

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
polarityWhether the limit switch is normally open or normally closed.
Deprecated:
Use GetForwardLimitSwitch(SparkMaxLimitSwitch::Type) instead

◆ GetReverseLimitSwitch() [1/3]

SparkLimitSwitch CANSparkBase::GetReverseLimitSwitch ( SparkLimitSwitch::Type  switchType)

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
switchTypeWhether the limit switch is normally open or normally closed.

◆ GetReverseLimitSwitch() [2/3]

SparkLimitSwitch CANSparkBase::GetReverseLimitSwitch ( SparkMaxLimitSwitch::Type  switchType)

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
switchTypeWhether the limit switch is normally open or normally closed.
Deprecated:
Use GetReverseLimitSwitch(SparkLimitSwitch::Type) instead

◆ GetReverseLimitSwitch() [3/3]

SparkLimitSwitch CANSparkBase::GetReverseLimitSwitch ( CANDigitalInput::LimitSwitchPolarity  polarity)

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
polarityWhether the limit switch is normally open or normally closed.
Deprecated:
Use GetReverseLimitSwitch(SparkMaxLimitSwitch::Type) instead

◆ SetSmartCurrentLimit() [1/2]

REVLibError CANSparkBase::SetSmartCurrentLimit ( unsigned int  limit)

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
limitThe current limit in Amps.

◆ SetSmartCurrentLimit() [2/2]

REVLibError CANSparkBase::SetSmartCurrentLimit ( unsigned int  stallLimit,
unsigned int  freeLimit,
unsigned int  limitRPM = 20000 
)

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
stallLimitThe current limit in Amps at 0 RPM.
freeLimitThe current limit at free speed (5700RPM for NEO).
limitRPMRPM less than this value will be set to the stallLimit, RPM values greater than limitRPM will scale linearly to freeLimit

◆ SetSecondaryCurrentLimit()

REVLibError CANSparkBase::SetSecondaryCurrentLimit ( double  limit,
int  limitCycles = 0 
)

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
limitThe current limit in Amps.
limitCyclesThe number of additional PWM cycles to turn the driver off after overcurrent is detected.

◆ SetIdleMode()

REVLibError CANSparkBase::SetIdleMode ( IdleMode  mode)

Sets the idle mode setting for the SPARK.

Parameters
modeIdle mode (coast or brake).

◆ GetIdleMode()

CANSparkBase::IdleMode CANSparkBase::GetIdleMode ( )

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

◆ EnableVoltageCompensation()

REVLibError CANSparkBase::EnableVoltageCompensation ( double  nominalVoltage)

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

Parameters
nominalVoltageNominal voltage to compensate output to
Returns
REVLibError::kOk if successful

◆ DisableVoltageCompensation()

REVLibError CANSparkBase::DisableVoltageCompensation ( )

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

Returns
REVLibError::kOk if successful

◆ GetVoltageCompensationNominalVoltage()

double CANSparkBase::GetVoltageCompensationNominalVoltage ( )

Get the configured voltage compensation nominal voltage value

Returns
The nominal voltage for voltage compensation mode.

◆ SetOpenLoopRampRate()

REVLibError CANSparkBase::SetOpenLoopRampRate ( double  rate)

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
rateTime in seconds to go from 0 to full throttle.

◆ SetClosedLoopRampRate()

REVLibError CANSparkBase::SetClosedLoopRampRate ( double  rate)

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
rateTime in seconds to go from 0 to full throttle.

◆ GetOpenLoopRampRate()

double CANSparkBase::GetOpenLoopRampRate ( )

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.

◆ GetClosedLoopRampRate()

double CANSparkBase::GetClosedLoopRampRate ( )

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.

◆ Follow() [1/2]

REVLibError CANSparkBase::Follow ( const CANSparkBase leader,
bool  invert = false 
)

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
leaderThe motor controller to follow.
invertSet the follower to output opposite of the leader

◆ Follow() [2/2]

REVLibError CANSparkBase::Follow ( ExternalFollower  leader,
int  deviceID,
bool  invert = false 
)

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
leaderThe type of motor controller to follow (Talon SRX, Spark Max, etc.).
deviceIDThe CAN ID of the device to follow.
invertSet the follower to output opposite of the leader

◆ IsFollower()

bool CANSparkBase::IsFollower ( )

Returns whether the controller is following another controller

Returns
True if this device is following another controller false otherwise

◆ GetFaults()

uint16_t CANSparkBase::GetFaults ( )

Returns fault bits.

◆ GetStickyFaults()

uint16_t CANSparkBase::GetStickyFaults ( )

Returns sticky fault bits.

◆ GetFault()

bool CANSparkBase::GetFault ( FaultID  faultID) const

Returns whether the fault with the given ID occurred.

◆ GetStickyFault()

bool CANSparkBase::GetStickyFault ( FaultID  faultID) const

Returns whether the sticky fault with the given ID occurred.

◆ GetBusVoltage()

double CANSparkBase::GetBusVoltage ( )

Returns the voltage fed into the motor controller.

◆ GetAppliedOutput()

double CANSparkBase::GetAppliedOutput ( )

Returns motor controller's output duty cycle.

◆ GetOutputCurrent()

double CANSparkBase::GetOutputCurrent ( )

Returns motor controller's output current in Amps.

◆ GetMotorTemperature()

double CANSparkBase::GetMotorTemperature ( )

Returns the motor temperature in Celsius.

◆ ClearFaults()

REVLibError CANSparkBase::ClearFaults ( )

Clears all non-sticky faults.

Sticky faults must be cleared by resetting the motor controller.

◆ BurnFlash()

REVLibError CANSparkBase::BurnFlash ( )

Writes all settings to flash.

◆ SetCANTimeout()

REVLibError CANSparkBase::SetCANTimeout ( int  milliseconds)

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
millisecondsThe timeout in milliseconds.

◆ EnableSoftLimit()

REVLibError CANSparkBase::EnableSoftLimit ( SoftLimitDirection  direction,
bool  enable 
)

Enable soft limits

Parameters
directionthe direction of motion to restrict
enableset true to enable soft limits

◆ IsSoftLimitEnabled()

bool CANSparkBase::IsSoftLimitEnabled ( CANSparkBase::SoftLimitDirection  direction)

Returns true if the soft limit is enabled.

◆ SetSoftLimit()

REVLibError CANSparkBase::SetSoftLimit ( CANSparkBase::SoftLimitDirection  direction,
double  limit 
)

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
directionthe direction of motion to restrict
limitposition soft limit of the controller

◆ GetSoftLimit()

double CANSparkBase::GetSoftLimit ( CANSparkBase::SoftLimitDirection  direction)

Get the soft limit setting in the controller

Parameters
directionthe direction of motion to restrict
Returns
position soft limit setting of the controller

◆ GetLastError()

REVLibError CANSparkBase::GetLastError ( )

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.

◆ attemptToSetDataportConfigOrThrow()

void CANSparkBase::attemptToSetDataportConfigOrThrow ( c_SparkMax_DataPortConfig  config,
std::string  errorText 
)
protected

Attempt to set the Dataport configuration for this device.

This method is currently a no-op on the Flex, and is intended for the SPARK MAX.

This method will throw an exception if an incompatible configuration is already active.

Parameters
configthe dataport configuration to attempt to set

Friends And Related Function Documentation

◆ CANSparkMax

friend class CANSparkMax
friend

◆ CANSparkFlex

friend class CANSparkFlex
friend

◆ SparkMaxLimitSwitch

friend class SparkMaxLimitSwitch
friend

◆ SparkMaxRelativeEncoder

friend class SparkMaxRelativeEncoder
friend

◆ SparkMaxAlternateEncoder

friend class SparkMaxAlternateEncoder
friend

◆ SparkMaxAbsoluteEncoder

friend class SparkMaxAbsoluteEncoder
friend

◆ ::ConfigBase

friend class ::ConfigBase
friend

Member Data Documentation

◆ kFollowerDisabled

constexpr CANSparkBase::ExternalFollower CANSparkBase::kFollowerDisabled {0, 0}
staticconstexpr

◆ kFollowerSparkMax

constexpr CANSparkBase::ExternalFollower CANSparkBase::kFollowerSparkMax {0x2051800, 26}
staticconstexpr
Deprecated:
Use kFollowerSpark instead

◆ kFollowerSpark

constexpr ExternalFollower rev::CANSparkBase::kFollowerSpark {0x2051800, 26}
staticconstexpr

◆ kFollowerPhoenix

constexpr CANSparkBase::ExternalFollower CANSparkBase::kFollowerPhoenix {0x2040080, 27}
staticconstexpr

The documentation for this class was generated from the following files: