REVLib - C++
rev::CANSparkMax Class Reference

#include <CANSparkMax.h>

Inherits rev::CANSparkBase.

Public Member Functions

 CANSparkMax (int deviceID, MotorType type)
 
 CANSparkMax (int deviceID, CANSparkMaxLowLevel::MotorType type)
 
 ~CANSparkMax () override=default
 
SparkRelativeEncoder GetEncoder ()
 
SparkMaxAlternateEncoder GetAlternateEncoder (int countsPerRev)
 
SparkMaxAlternateEncoder GetAlternateEncoder (SparkMaxAlternateEncoder::Type encoderType, int countsPerRev)
 
SparkMaxAlternateEncoder GetAlternateEncoder (CANEncoder::AlternateEncoderType encoderType, int countsPerRev)
 
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)
 
- Public Member Functions inherited from rev::CANSparkBase
 ~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
 
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)
 

Friends

class SparkMaxAlternateEncoder
 

Additional Inherited Members

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

Constructor & Destructor Documentation

◆ CANSparkMax() [1/2]

CANSparkMax::CANSparkMax ( int  deviceID,
MotorType  type 
)
explicit

Create a new object to control a SPARK MAX motor Controller

Parameters
deviceIDThe device ID.
typeThe motor type connected to the controller. Brushless motor wires must be connected to their matching colors, and the hall sensor must be plugged in. Brushed motors must be connected to the Red and Black terminals only.

◆ CANSparkMax() [2/2]

CANSparkMax::CANSparkMax ( int  deviceID,
CANSparkMaxLowLevel::MotorType  type 
)
explicit

Create a new object to control a SPARK MAX motor Controller

Parameters
deviceIDThe device ID.
typeThe motor type connected to the controller. Brushless motor wires must be connected to their matching colors, and the hall sensor must be plugged in. Brushed motors must be connected to the Red and Black terminals only.
Deprecated:
Use CANSparkMax(int, CANSparkLowLevel::MotorType) instead

◆ ~CANSparkMax()

rev::CANSparkMax::~CANSparkMax ( )
overridedefault

Closes the SPARK MAX Controller

Member Function Documentation

◆ GetEncoder() [1/5]

SparkRelativeEncoder CANSparkMax::GetEncoder ( )
virtual

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

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.

Implements rev::CANSparkBase.

◆ GetAlternateEncoder() [1/3]

SparkMaxAlternateEncoder CANSparkMax::GetAlternateEncoder ( int  countsPerRev)

Returns an object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins. These are defined as:

Pin 4 (Forward Limit Switch): Index Pin 6 (Multi-function): Encoder A Pin 8 (Reverse Limit Switch): Encoder B

This call will disable support for the limit switch inputs.

◆ GetAlternateEncoder() [2/3]

SparkMaxAlternateEncoder CANSparkMax::GetAlternateEncoder ( SparkMaxAlternateEncoder::Type  encoderType,
int  countsPerRev 
)

Returns an object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins. These are defined as:

Pin 4 (Forward Limit Switch): Index Pin 6 (Multi-function): Encoder A Pin 8 (Reverse Limit Switch): Encoder B

This call will disable support for the limit switch inputs.

◆ GetAlternateEncoder() [3/3]

SparkMaxAlternateEncoder CANSparkMax::GetAlternateEncoder ( CANEncoder::AlternateEncoderType  encoderType,
int  countsPerRev 
)

Returns an object for interfacing with a quadrature encoder connected to the alternate encoder mode data port pins. These are defined as:

Pin 4 (Forward Limit Switch): Index Pin 6 (Multi-function): Encoder A Pin 8 (Reverse Limit Switch): Encoder B

This call will disable support for the limit switch inputs.

Deprecated:
Use CANSparkBase::GetAlternateEncoder(SparkMaxAlternateEncoder::Type, int) instead

◆ GetEncoder() [2/5]

virtual SparkRelativeEncoder rev::CANSparkBase::GetEncoder ( )
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.

Implements rev::CANSparkBase.

◆ GetEncoder() [3/5]

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() [4/5]

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() [5/5]

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

Friends And Related Function Documentation

◆ SparkMaxAlternateEncoder

friend class SparkMaxAlternateEncoder
friend

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