#include <CANSparkMax.h>
Inherits rev::CANSparkMaxLowLevel.
|
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
} |
|
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
} |
|
enum class | TelemetryID {
kBusVoltage = 0
, kOutputCurrent
, kVelocity
, kPosition
,
kIAccum
, kAppliedOutput
, kMotorTemp
, kFaults
,
kStickyFaults
, kAnalogVoltage
, kAnalogPosition
, kAnalogVelocity
,
kAltEncPosition
, kAltEncVelocity
, kTotalStreams
} |
|
|
| CANSparkMax (int deviceID, MotorType type) |
|
| ~CANSparkMax () 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 |
|
SparkMaxRelativeEncoder | GetEncoder (SparkMaxRelativeEncoder::Type encoderType=SparkMaxRelativeEncoder::Type::kHallSensor, int countsPerRev=42) |
|
SparkMaxRelativeEncoder | GetEncoder (CANEncoder::EncoderType encoderType, int countsPerRev) |
|
SparkMaxAlternateEncoder | GetAlternateEncoder (int countsPerRev) |
|
SparkMaxAlternateEncoder | GetAlternateEncoder (SparkMaxAlternateEncoder::Type encoderType, int countsPerRev) |
|
SparkMaxAlternateEncoder | GetAlternateEncoder (CANEncoder::AlternateEncoderType encoderType, int countsPerRev) |
|
SparkMaxAnalogSensor | GetAnalog (SparkMaxAnalogSensor::Mode mode=SparkMaxAnalogSensor::Mode::kAbsolute) |
|
SparkMaxAnalogSensor | GetAnalog (CANAnalog::AnalogMode mode) |
|
SparkMaxPIDController | GetPIDController () |
|
SparkMaxLimitSwitch | GetForwardLimitSwitch (SparkMaxLimitSwitch::Type switchType) |
|
SparkMaxLimitSwitch | GetForwardLimitSwitch (CANDigitalInput::LimitSwitchPolarity polarity) |
|
SparkMaxLimitSwitch | GetReverseLimitSwitch (SparkMaxLimitSwitch::Type switchType) |
|
SparkMaxLimitSwitch | 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 CANSparkMax &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 () |
|
virtual | ~CANSparkMaxLowLevel () |
|
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) |
|
void | SetControlFramePeriodMs (int periodMs) |
|
REVLibError | RestoreFactoryDefaults (bool persist=false) |
|
◆ IdleMode
◆ InputMode
◆ SoftLimitDirection
Enumerator |
---|
kForward | |
kReverse | |
◆ FaultID
Enumerator |
---|
kBrownout | |
kOvercurrent | |
kIWDTReset | |
kMotorFault | |
kSensorFault | |
kStall | |
kEEPROMCRC | |
kCANTX | |
kCANRX | |
kHasReset | |
kDRVFault | |
kOtherFault | |
kSoftLimitFwd | |
kSoftLimitRev | |
kHardLimitFwd | |
kHardLimitRev | |
◆ CANSparkMax()
CANSparkMax::CANSparkMax |
( |
int |
deviceID, |
|
|
MotorType |
type |
|
) |
| |
|
explicit |
Create a new object to control a SPARK MAX motor Controller
- Parameters
-
deviceID | The device ID. |
type | The 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()
rev::CANSparkMax::~CANSparkMax |
( |
| ) |
|
|
overridedefault |
Closes the SPARK MAX Controller
◆ Set()
void CANSparkMax::Set |
( |
double |
speed | ) |
|
|
override |
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. |
◆ SetVoltage()
void CANSparkMax::SetVoltage |
( |
units::volt_t |
output | ) |
|
|
override |
Sets the voltage output of the SpeedController. This is equivalent to a call to SetReference(output, CANSparkMax::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. |
◆ 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.
◆ 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. To invert a follower, see the follow() method.
- Parameters
-
isInverted | The state of inversion, true is inverted. |
◆ 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.
◆ Disable()
void CANSparkMax::Disable |
( |
| ) |
|
|
override |
Common interface for disabling a motor.
◆ StopMotor()
void CANSparkMax::StopMotor |
( |
| ) |
|
|
override |
Common interface to stop the motor until Set is called again.
◆ GetEncoder() [1/2]
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.
◆ GetEncoder() [2/2]
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.
- Deprecated:
- Use CANSparkMax::GetEncoder(SparkMaxRelativeEncoder::Type, int) instead
◆ GetAlternateEncoder() [1/3]
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]
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]
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 CANSparkMax::GetAlternateEncoder(SparkMaxAlternateEncoder::Type, int) instead
◆ GetAnalog() [1/2]
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/2]
◆ GetPIDController()
Returns an object for interfacing with the integrated PID controller.
◆ GetForwardLimitSwitch() [1/2]
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. |
◆ GetForwardLimitSwitch() [2/2]
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
-
polarity | Whether the limit switch is normally open or normally closed. |
- Deprecated:
- Use GetForwardLimitSwitch(SparkMaxLimitSwitch::Type) instead
◆ GetReverseLimitSwitch() [1/2]
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. |
◆ GetReverseLimitSwitch() [2/2]
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
-
polarity | Whether the limit switch is normally open or normally closed. |
- Deprecated:
- Use GetReverseLimitSwitch(SparkMaxLimitSwitch::Type) instead
◆ SetSmartCurrentLimit() [1/2]
REVLibError 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
-
limit | The current limit in Amps. |
◆ SetSmartCurrentLimit() [2/2]
REVLibError 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
-
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 |
◆ SetSecondaryCurrentLimit()
REVLibError 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
-
limit | The current limit in Amps. |
limitCycles | The number of additional PWM cycles to turn the driver off after overcurrent is detected. |
◆ SetIdleMode()
Sets the idle mode setting for the SPARK MAX.
- Parameters
-
mode | Idle mode (coast or brake). |
◆ 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
◆ EnableVoltageCompensation()
REVLibError CANSparkMax::EnableVoltageCompensation |
( |
double |
nominalVoltage | ) |
|
Sets the voltage compensation setting for all modes on the SPARK MAX and enables voltage compensation.
- Parameters
-
nominalVoltage | Nominal voltage to compensate output to |
- Returns
- REVLibError::kOk if successful
◆ DisableVoltageCompensation()
REVLibError CANSparkMax::DisableVoltageCompensation |
( |
| ) |
|
Disables the voltage compensation setting for all modes on the SPARK MAX.
- Returns
- REVLibError::kOk if successful
◆ GetVoltageCompensationNominalVoltage()
double CANSparkMax::GetVoltageCompensationNominalVoltage |
( |
| ) |
|
Get the configured voltage compensation nominal voltage value
- Returns
- The nominal voltage for voltage compensation mode.
◆ SetOpenLoopRampRate()
REVLibError 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
-
rate | Time in seconds to go from 0 to full throttle. |
◆ SetClosedLoopRampRate()
REVLibError 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
-
rate | Time in seconds to go from 0 to full throttle. |
◆ 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.
◆ 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.
◆ Follow() [1/2]
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
-
leader | The motor controller to follow. |
invert | Set the follower to output opposite of the leader |
◆ Follow() [2/2]
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
-
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 |
◆ IsFollower()
bool CANSparkMax::IsFollower |
( |
| ) |
|
Returns whether the controller is following another controller
- Returns
- True if this device is following another controller false otherwise
◆ GetFaults()
uint16_t CANSparkMax::GetFaults |
( |
| ) |
|
◆ GetStickyFaults()
uint16_t CANSparkMax::GetStickyFaults |
( |
| ) |
|
Returns sticky fault bits.
◆ GetFault()
bool CANSparkMax::GetFault |
( |
FaultID |
faultID | ) |
const |
Returns whether the fault with the given ID occurred.
◆ GetStickyFault()
bool CANSparkMax::GetStickyFault |
( |
FaultID |
faultID | ) |
const |
Returns whether the sticky fault with the given ID occurred.
◆ GetBusVoltage()
double CANSparkMax::GetBusVoltage |
( |
| ) |
|
Returns the voltage fed into the motor controller.
◆ GetAppliedOutput()
double CANSparkMax::GetAppliedOutput |
( |
| ) |
|
Returns motor controller's output duty cycle.
◆ GetOutputCurrent()
double CANSparkMax::GetOutputCurrent |
( |
| ) |
|
Returns motor controller's output current in Amps.
◆ GetMotorTemperature()
double CANSparkMax::GetMotorTemperature |
( |
| ) |
|
Returns the motor temperature in Celsius.
◆ ClearFaults()
Clears all non-sticky faults.
Sticky faults must be cleared by resetting the motor controller.
◆ BurnFlash()
Writes all settings to flash.
◆ SetCANTimeout()
REVLibError 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
-
milliseconds | The timeout in milliseconds. |
◆ EnableSoftLimit()
Enable soft limits
- Parameters
-
direction | the direction of motion to restrict |
enable | set true to enable soft limits |
◆ IsSoftLimitEnabled()
Returns true if the soft limit is enabled.
◆ SetSoftLimit()
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 |
◆ GetSoftLimit()
Get the soft limit setting in the controller
- Parameters
-
direction | the direction of motion to restrict |
- Returns
- position soft limit setting of the controller
◆ 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.
◆ SparkMaxAlternateEncoder
◆ SparkMaxLimitSwitch
◆ SparkMaxRelativeEncoder
◆ ::ConfigBase
friend class ::ConfigBase |
|
friend |
◆ kFollowerDisabled
◆ kFollowerSparkMax
◆ kFollowerPhoenix
The documentation for this class was generated from the following files: