SPARK MAX - C++ Documentation
rev::CANSparkMax Class Reference

Inherits rev::CANSparkMaxLowLevel, and rev::CANStreamable< c_SparkMax_TelemetryID, c_SparkMax_TelemetryMessage >.

Classes

struct  ExternalFollower
 

Public Types

enum  IdleMode { kCoast = 0, kBrake = 1 }
 
enum  InputMode { kPWM = 0, kCAN = 1 }
 
enum  SoftLimitDirection { kForward, kReverse }
 
enum  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::CANSparkMaxLowLevel
enum  MotorType { kBrushed = 0, kBrushless = 1 }
 
enum  ParameterStatus {
  kOK = 0, kInvalidID = 1, kMismatchType = 2, kAccessMode = 3,
  kInvalid = 4, kNotImplementedDeprecated = 5
}
 
enum  PeriodicFrame { kStatus0 = 0, kStatus1 = 1, kStatus2 = 2 }
 

Public Member Functions

 CANSparkMax (int deviceID, MotorType type)
 
 ~CANSparkMax () override=default
 
void Set (double speed) override
 
double Get () const override
 
void SetInverted (bool isInverted) override
 
bool GetInverted () const override
 
void Disable () override
 
void StopMotor () override
 
void PIDWrite (double output) override
 
CANEncoder GetEncoder (CANEncoder::EncoderType sensorType=CANEncoder::EncoderType::kHallSensor, int counts_per_rev=0)
 
CANEncoder GetAlternateEncoder (CANEncoder::AlternateEncoderType sensorType, int counts_per_rev)
 
CANAnalog GetAnalog (CANAnalog::AnalogMode mode=CANAnalog::AnalogMode::kAbsolute)
 
CANPIDController GetPIDController ()
 
CANDigitalInput GetForwardLimitSwitch (CANDigitalInput::LimitSwitchPolarity polarity)
 
CANDigitalInput GetReverseLimitSwitch (CANDigitalInput::LimitSwitchPolarity polarity)
 
CANError SetSmartCurrentLimit (unsigned int limit)
 
CANError SetSmartCurrentLimit (unsigned int stallLimit, unsigned int freeLimit, unsigned int limitRPM=20000)
 
CANError SetSecondaryCurrentLimit (double limit, int limitCycles=0)
 
CANError SetIdleMode (IdleMode mode)
 
IdleMode GetIdleMode ()
 
CANError EnableVoltageCompensation (double nominalVoltage)
 
CANError DisableVoltageCompensation ()
 
double GetVoltageCompensationNominalVoltage ()
 
CANError SetOpenLoopRampRate (double rate)
 
CANError SetClosedLoopRampRate (double rate)
 
double GetOpenLoopRampRate ()
 
double GetClosedLoopRampRate ()
 
CANError Follow (const CANSparkMax &leader, bool invert=false)
 
CANError Follow (ExternalFollower leader, int deviceID, bool invert=false)
 
bool IsFollower ()
 
uint16_t GetFaults ()
 
uint16_t GetStickyFaults ()
 
bool GetFault (FaultID faultID)
 
bool GetStickyFault (FaultID faultID)
 
double GetBusVoltage ()
 
double GetAppliedOutput ()
 
double GetOutputCurrent ()
 
double GetMotorTemperature ()
 
CANError ClearFaults ()
 
CANError BurnFlash ()
 
CANError SetCANTimeout (int milliseconds)
 
CANError EnableSoftLimit (SoftLimitDirection direction, bool enable)
 
bool IsSoftLimitEnabled (SoftLimitDirection direction)
 
CANError SetSoftLimit (SoftLimitDirection direction, double limit)
 
double GetSoftLimit (SoftLimitDirection direction)
 
CANError GetLastError ()
 
void StartStream () override
 
void ReadStream (std::vector< c_SparkMax_TelemetryID > &streams, std::vector< c_SparkMax_TelemetryMessage > *messages) override
 
void CloseStream () override
 
void ListStreamable (std::vector< c_SparkMax_TelemetryMessage > &streams) override
 
- Public Member Functions inherited from rev::CANSparkMaxLowLevel
 CANSparkMaxLowLevel (int deviceID, MotorType type)
 
 ~CANSparkMaxLowLevel ()
 
uint32_t GetFirmwareVersion ()
 
uint32_t GetFirmwareVersion (bool &isDebugBuild)
 
std::string GetFirmwareString ()
 
std::vector< uint8_t > GetSerialNumber ()
 
int GetDeviceId () const
 
MotorType GetInitialMotorType ()
 
CANError SetMotorType (MotorType type)
 
MotorType GetMotorType ()
 
CANError SetPeriodicFramePeriod (PeriodicFrame frame, int periodMs)
 
void SetControlFramePeriodMs (int periodMs)
 
CANError RestoreFactoryDefaults (bool persist=false)
 
- Public Member Functions inherited from rev::CANStreamable< c_SparkMax_TelemetryID, c_SparkMax_TelemetryMessage >
 CANStreamable ()
 

Static Public Attributes

static constexpr ExternalFollower kFollowerDisabled {0, 0}
 
static constexpr ExternalFollower kFollowerSparkMax {0x2051800, 26}
 
static constexpr ExternalFollower kFollowerPhoenix {0x2040080, 27}
 
- Static Public Attributes inherited from rev::CANSparkMaxLowLevel
static const uint8_t kAPIMajorVersion
 
static const uint8_t kAPIMinorVersion
 
static const uint8_t kAPIBuildVersion
 
static const uint32_t kAPIVersion
 

Friends

class CANDigitalInput
 
class CANEncoder
 

Additional Inherited Members

- Static Public Member Functions inherited from rev::CANSparkMaxLowLevel
static void EnableExternalUSBControl (bool enable)
 
static void SetEnable (bool enable)
 
- Protected Member Functions inherited from rev::CANSparkMaxLowLevel
CANError SetEncPosition (double value)
 
CANError SetIAccum (double value)
 
PeriodicStatus0 GetPeriodicStatus0 ()
 
PeriodicStatus1 GetPeriodicStatus1 ()
 
PeriodicStatus2 GetPeriodicStatus2 ()
 
CANError SetFollow (FollowConfig config)
 
CANError FollowerInvert (bool invert)
 
CANError SetpointCommand (double value, ControlType ctrl=ControlType::kDutyCycle, int pidSlot=0, double arbFeedforward=0, int arbFFUnits=0)
 
float GetSafeFloat (float f)
 
- Protected Attributes inherited from rev::CANSparkMaxLowLevel
void * m_sparkMax
 
MotorType m_motorType
 

Constructor & Destructor Documentation

◆ CANSparkMax()

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

Create a new SPARK MAX Controller

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

◆ ~CANSparkMax()

rev::CANSparkMax::~CANSparkMax ( )
overridedefault

Closes the SPARK MAX Controller

Member Function Documentation

◆ BurnFlash()

CANError CANSparkMax::BurnFlash ( )

Writes all settings to flash.

◆ ClearFaults()

CANError CANSparkMax::ClearFaults ( )

Clears all non-sticky faults.

Sticky faults must be cleared by resetting the motor controller.

◆ CloseStream()

void CANSparkMax::CloseStream ( )
overridevirtual

Using predefined Stream IDs. Closes multiple streams at once.

Implements rev::CANStreamable< c_SparkMax_TelemetryID, c_SparkMax_TelemetryMessage >.

◆ Disable()

void CANSparkMax::Disable ( )
override

Common interface for disabling a motor.

◆ DisableVoltageCompensation()

CANError CANSparkMax::DisableVoltageCompensation ( )

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

Returns
CANError Set to CANError.kOK if successful

◆ EnableSoftLimit()

CANError CANSparkMax::EnableSoftLimit ( SoftLimitDirection  direction,
bool  enable 
)

Enable soft limits

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

◆ EnableVoltageCompensation()

CANError CANSparkMax::EnableVoltageCompensation ( double  nominalVoltage)

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

Parameters
nominalVoltageNominal voltage to compensate output to
Returns
CANError Set to CANError.kOK if successful

◆ Follow() [1/2]

CANError CANSparkMax::Follow ( const CANSparkMax 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 SPARK MAX is not officially supported.

Parameters
leaderThe motor controller to follow.
invertSet the follower to output opposite of the leader

◆ Follow() [2/2]

CANError CANSparkMax::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 SPARK MAX 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

◆ Get()

double CANSparkMax::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.

◆ GetAlternateEncoder()

CANEncoder CANSparkMax::GetAlternateEncoder ( CANEncoder::AlternateEncoderType  sensorType,
int  counts_per_rev 
)

Returns an object for interfacing with the encoder connected to the alternate data port configured pins. This is defined as:

Multi-function Pin: Encoder A Limit Switch Reverse : Encoder B

This call will disable the limit switch inputs.

◆ GetAnalog()

CANAnalog CANSparkMax::GetAnalog ( CANAnalog::AnalogMode  mode = CANAnalog::AnalogMode::kAbsolute)

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

◆ GetAppliedOutput()

double CANSparkMax::GetAppliedOutput ( )

Returns motor controller's output duty cycle.

◆ GetBusVoltage()

double CANSparkMax::GetBusVoltage ( )

Returns the voltage fed into the motor controller.

◆ GetClosedLoopRampRate()

double CANSparkMax::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.

◆ GetEncoder()

CANEncoder CANSparkMax::GetEncoder ( CANEncoder::EncoderType  sensorType = CANEncoder::EncoderType::kHallSensor,
int  counts_per_rev = 0 
)

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

The default encoder type is assumed to be the hall effect for brushless. This can be modified for brushed DC to use an quadrature encoder.

◆ GetFault()

bool CANSparkMax::GetFault ( FaultID  faultID)

Returns whether the fault with the given ID occurred.

◆ GetFaults()

uint16_t CANSparkMax::GetFaults ( )

Returns fault bits.

◆ GetForwardLimitSwitch()

CANDigitalInput CANSparkMax::GetForwardLimitSwitch ( CANDigitalInput::LimitSwitchPolarity  polarity)

Returns an object for interfacing with the integrated forward limit switch.

Parameters
polarityWhether the limit switch is normally open or normally closed.

◆ GetIdleMode()

CANSparkMax::IdleMode CANSparkMax::GetIdleMode ( )

Gets the idle mode setting for the SPARK MAX.

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 CANSparkMax::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.

◆ GetLastError()

CANError CANSparkMax::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.

◆ GetMotorTemperature()

double CANSparkMax::GetMotorTemperature ( )

Returns the motor temperature in Celsius.

◆ GetOpenLoopRampRate()

double CANSparkMax::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.

◆ GetOutputCurrent()

double CANSparkMax::GetOutputCurrent ( )

Returns motor controller's output current in Amps.

◆ GetPIDController()

CANPIDController CANSparkMax::GetPIDController ( )

Returns an object for interfacing with the integrated PID controller.

◆ GetReverseLimitSwitch()

CANDigitalInput CANSparkMax::GetReverseLimitSwitch ( CANDigitalInput::LimitSwitchPolarity  polarity)

Returns an object for interfacing with the integrated reverse limit switch.

Parameters
polarityWhether the limit switch is normally open or normally closed.

◆ GetSoftLimit()

double CANSparkMax::GetSoftLimit ( CANSparkMax::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

◆ GetStickyFault()

bool CANSparkMax::GetStickyFault ( FaultID  faultID)

Returns whether the sticky fault with the given ID occurred.

◆ GetStickyFaults()

uint16_t CANSparkMax::GetStickyFaults ( )

Returns sticky fault bits.

◆ GetVoltageCompensationNominalVoltage()

double CANSparkMax::GetVoltageCompensationNominalVoltage ( )

Get the configured voltage compensation nominal voltage value

Returns
The nominal voltage for voltage compensation mode.

◆ IsFollower()

bool CANSparkMax::IsFollower ( )

Returns whether the controller is following another controller

Returns
True if this device is following another controller false otherwise

◆ IsSoftLimitEnabled()

bool CANSparkMax::IsSoftLimitEnabled ( CANSparkMax::SoftLimitDirection  direction)

Returns true if the soft limit is enabled.

◆ ReadStream()

void CANSparkMax::ReadStream ( std::vector< c_SparkMax_TelemetryID > &  streams,
std::vector< c_SparkMax_TelemetryMessage > *  messages 
)
overridevirtual

Using predefined Stream IDs. Reads back data from the given streams in the form of StreamMessages

Implements rev::CANStreamable< c_SparkMax_TelemetryID, c_SparkMax_TelemetryMessage >.

◆ Set()

void CANSparkMax::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.

◆ SetCANTimeout()

CANError CANSparkMax::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.

◆ SetClosedLoopRampRate()

CANError CANSparkMax::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.

◆ SetIdleMode()

CANError CANSparkMax::SetIdleMode ( IdleMode  mode)

Sets the idle mode setting for the SPARK MAX.

Parameters
modeIdle mode (coast or brake).

◆ SetInverted()

void CANSparkMax::SetInverted ( bool  isInverted)
override

Common interface for inverting direction of a speed controller.

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

Parameters
isInvertedThe state of inversion, true is inverted.

◆ SetOpenLoopRampRate()

CANError CANSparkMax::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.

◆ SetSecondaryCurrentLimit()

CANError CANSparkMax::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.

◆ SetSmartCurrentLimit() [1/2]

CANError CANSparkMax::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]

CANError CANSparkMax::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

◆ SetSoftLimit()

CANError CANSparkMax::SetSoftLimit ( CANSparkMax::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

◆ StartStream()

void CANSparkMax::StartStream ( )
overridevirtual

Using predefined Stream IDs. Starts multiple streams at once.

Implements rev::CANStreamable< c_SparkMax_TelemetryID, c_SparkMax_TelemetryMessage >.

◆ StopMotor()

void CANSparkMax::StopMotor ( )
override

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


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