Search…
Migrating from CTRE Phoenix to SPARK MAX
Many teams have been using various CTRE motor controllers such as the Talon SRX and Talon SPX, and have concerns about porting software between platforms. Fortunately the feature set and code required is similar between the two, and porting from one to the other is easy. Below shows the common tasks and the changes required to convert from the code for CTRE Phoenix devices to the SPARK MAX.

JAVA

Include Library

REV SPARK MAX
Phoenix Framework
1
import com.revrobotics.CANEncoder;
2
import com.revrobotics.CANPIDController;
3
import com.revrobotics.CANSparkMax;
4
import com.revrobotics.ControlType;
5
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
Copied!
1
import com.ctre.phoenix.motorcontrol.can.*;
2
import com.ctre.phoenix.motorcontrol.*;
Copied!

Create Object CAN ID 1

REV SPARK MAX
Phoenix Framework
1
private CANSparkMax sparkMax = new CANSparkMax(deviceID, MotorType.kBrushless);
Copied!
1
TalonSRX talonSRX = new TalonSRX(1);
Copied!

Reset Factory Defaults

REV SPARK MAX
Phoenix Framework
1
sparkMax.restoreFactoryDefaults();
Copied!
1
talonSRX.configFactoryDefault();
Copied!

Select Encoder

This is a brushed motor feature and not needed for using brushless motors with SPARK MAX
REV SPARK MAX
Phoenix Framework
1
encoder = sparkMax.getEncoder();
2
encoder.setInverted(false);
3
sparkMax.setFeedbackDevice(encoder);
Copied!
1
talonSRX.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, kPIDLoopIdx, Constants.kTimeoutMs);
2
talonSRX.setSensorPhase(true);
Copied!

Set closed loop constants

REV SPARK MAX
Phoenix Framework
1
pidController.setP(kP);
2
pidController.setI(kI);
3
pidController.setD(kD);
4
pidController.setIZone(kIz);
5
pidController.setFF(kFF);
6
pidController.setOutputRange(kMinOutput, kMaxOutput);
Copied!
1
talonSRX.configNominalOutputForward(0, kTimeoutMs);
2
talonSRX.configNominalOutputReverse(0, kTimeoutMs);
3
talonSRX.configPeakOutputForward(kMaxOutput, kTimeoutMs);
4
talonSRX.configPeakOutputReverse(kMinOutput, kTimeoutMs);
5
6
talonSRX.config_kF(kPIDLoopIdx, kP, kTimeoutMs);
7
talonSRX.config_kP(kPIDLoopIdx, kI, kTimeoutMs);
8
talonSRX.config_kI(kPIDLoopIdx, kD, kTimeoutMs);
9
talonSRX.config_kD(kPIDLoopIdx, kF, kTimeoutMs);
Copied!

Run Closed Loop Velocity Control

For this example velocity is set at 500 RPM
REV SPARK MAX
Phoenix Framework
1
pidController.setReference(500.0, ControlType.kVelocity);
Copied!
1
// Convert from 500 RPM to 'native units'
2
double VelocityinUnitsPer100ms = 500.0 * 4096 / 600;
3
talonSRX.set(ControlMode.Velocity, VelocityinUnitsPer100ms );
Copied!

Read RPM of Motor

REV SPARK MAX
Phoenix Framework
1
encoder.getVelocity();
Copied!
1
talonSRX.getSelectedSensorVelocity(kPIDLoopIdx) * 600 / 4096;
Copied!

Read Applied Output Percent

REV SPARK MAX
Phoenix Framework
1
sparkMax.getAppliedOutput();
Copied!
1
talonSRX.getMotorOutputPercent();
Copied!

Run Closed Loop Position Control

This example runs a position control loop for 10 rotations.
REV SPARK MAX
Phoenix Framework
1
pidController.setReference(10.0, ControlType.kPosition);
Copied!
1
targetPositionRoations = 10.0 * 4096;
2
talonSRX.set(ControlMode.Position, targetPositionRotations);
Copied!

Change Units from 'rotations' to 'inches'

This example assumes a 4" wheel on a 15:1 reduction
REV SPARK MAX
Phoenix Framwork
1
encoder.setPositionFactor(M_PI * 4/15);
Copied!
1
// No Equivellant
Copied!

Run Closed Loop Position Control for a set distance

This example assumes a 4" wheel on a 15:1 reduction to move 2 feet (24 inches).
REV SPARK MAX
Phoenix Framework
1
pidController.setReference(24.0, ControlType.kPosition);
Copied!
1
targetPositionRotations = (M_PI * 4 / 15 * 4096) * 24;
2
talonSRX.set(ControlMode.Position, targetPositionRotations);
Copied!

Save Parameters

REV SPARK MAX
Phoenix Framework
1
// Run after all parameters are set in RobotInit()
2
sparkMax.burnFlash();
Copied!
1
//Automatic
Copied!

Follow another device

REV SPARK MAX
Phoenix Framework
1
sparkMax1.follow(sparkMax2);
Copied!
1
talonSRX1.follow(talonSRX2);
Copied!

Invert a device

REV SPARK MAX
Phoenix Framework
1
sparkMax.setInverted(true);
Copied!
1
talonSRX.setInverted(true);
Copied!

Configure a limit switch

REV SPARK MAX
Phoenix Framework
1
forwardLimit = sparkMax.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyOpen);
Copied!
1
talonSRX.configForwardLimitSwitchSource(
2
LimitSwitchSource.LimitSwitchSource_FeedbackConnector,
3
LimitSwitchNormal.LimitSwitchNormal_NormallyOpen,
4
kTimeoutMs);
Copied!

Disable a limit switch

REV SPARK MAX
Phoenix Framework
1
forwardLimit.EnableLimitSwitch(false);
Copied!
1
talonSRX.overrideLimitSwitchesEnable(true);
Copied!

C++

Include Library

REV SPARK MAX
Phoenix Framework
1
#include "rev/CANSparkMax.h"
Copied!
1
#include "ctre/Phoenix.h"
Copied!

Create Object CAN ID 1

REV SPARK MAX
Phoenix Framework
1
rev::CANSparkMax sparkMax{1, rev::CANSparkMax::MotorType::kBrushless};
Copied!
1
TalonSRX* talon = new TalonSRX(1);
Copied!

Reset Factory Defaults

REV SPARK MAX
Phoenix Framework
1
sparkMax.RestoreFactoryDefaults();
Copied!
1
talon->ConfigFactoryDefault();
Copied!

Select Encoder

This is a brushed motor feature and not needed for using brushless motors with SPARK MAX.
REV SPARK MAX
Phoenix Framework
1
rev::CANEncoder encoder = sparkMax.GetEncoder(rev::CANEncoder::EncoderType::kQuadrature, 4096);
2
encoder.SetInverted(true);
3
sparkMax.SetFeedbackDevice(encoder);
Copied!
1
talonSRX->ConfigSelectedFeedbackSensor(FeedbackDevice::CTRE_MagEncoder_Relative, 0, kTimeoutMs);
2
talonSRX->SetSensorPhase(true);
Copied!

Set closed loop constants

REV SPARK MAX
Phoenix Framework
1
rev::CANPIDController pidController = sparkMax.GetPIDController();
2
pidController.SetFeedbackDevice(encoder);
3
4
pidController.SetP(kP);
5
pidController.SetI(kI);
6
pidController.SetD(kD);
7
pidController.SetIZone(kIz);
8
pidController.SetFF(kFF);
9
pidController.SetOutputRange(kMinOutput, kMaxOutput);
Copied!
1
talonSRX->ConfigNominalOutputForward(0, kTimeoutMs);
2
talonSRX->ConfigNominalOutputReverse(0, kTimeoutMs);
3
talonSRX->ConfigPeakOutputForward(1, kTimeoutMs);
4
talonSRX->ConfigPeakOutputReverse(-1, kTimeoutMs);
5
6
talonSRX->Config_kF(kPIDLoopIdx, 0.1097, kTimeoutMs);
7
talonSRX->Config_kP(kPIDLoopIdx, 0.22, kTimeoutMs);
8
talonSRX->Config_kI(kPIDLoopIdx, 0.0, kTimeoutMs);
9
talonSRX->Config_kD(kPIDLoopIdx, 0.0, kTimeoutMs);
Copied!

Run Closed Loop Velocity Control

For this example velocity is set at 500 RPM
REV SPARK MAX
Phoenix Framework
1
pidController.SetReference(500.0, rev::ControlType::kVelocity);
Copied!
1
"// Convert from 500 RPM to 'native units'
2
double VelocityinUnitsPer100ms = 500.0 * 4096 / 600;
3
talonSRX->Set(ControlMode::Velocity, VelocityinUnitsPer100ms );
Copied!

Read RPM of Motor

REV SPARK MAX
Phoenix Framework
1
encoder.GetVelocity();
Copied!
1
talonSRX->GetSelectedSensorVelocity(kPIDLoopIdx) * 600 / 4096;
Copied!

Read Applied Output Percent

REV SPARK MAX
Phoenix Framework
1
sparkMax.GetAppliedOutput();
Copied!
1
talonSRX->GetMotorOutputPercent();
Copied!

Run Closed Loop Position Control

This example runs a position control loop for 10 rotations.
REV SPARK MAX
Phoenix Framework
1
pidController.SetReference(10.0, rev::ControlType::kPosition);
Copied!
1
targetPositionRotations = 10.0 * 4096;
2
talonSRX->Set(ControlMode::Position, targetPositionRotations);;
Copied!

Change Units from 'rotations' to 'inches'

This example assumes a 4" wheel on a 15:1 reduction
REV SPARK MAX
Phoenix Framwork
1
encoder.SetPositionFactor( M_PI * 4 / 15 );
Copied!
1
// No Equivellant
Copied!

Run Closed Loop Position Control for a set distance

This example assumes a 4" wheel on a 15:1 reduction to move 2 feet (24 inches).
REV SPARK MAX
Phoenix Framework
1
pidController.SetReference(24.0, rev::ControlType::kPosition);
Copied!
1
targetPositionRotations = (M_PI * 4 / 15 * 4096) * 24;
2
talonSRX->Set(ControlMode::Position, targetPositionRotations);
Copied!

Save Parameters

REV SPARK MAX
Phoenix Framework
1
// Run after all parameters are set in RobotInit()
2
sparkMax.BurnFlash();
Copied!
1
//Automatic
Copied!

Follow another device

REV SPARK MAX
Phoenix Framework
1
sparkMax1.Follow(sparkMax2);
Copied!
1
talonSRX1->Follow(*talon2);
Copied!

Invert a device

REV SPARK MAX
Phoenix Framework
1
sparkMax.SetInverted(true);
Copied!
1
talonSRX->SetInverted(true);
Copied!

Configure a limit switch

REV SPARK MAX
Phoenix Framework
1
rev::CANDigitalInput forwardLimit = sparkMax.GetForwardLimitSwitch(rev::CANDigitalInput::LimitSwitchPolarity::kNormallyOpen);
Copied!
1
talonSRX->ConfigForwardLimitSwitchSource(
2
LimitSwitchSource::LimitSwitchSource_FeedbackConnector,
3
LimitSwitchNormal::LimitSwitchNormal_NormallyOpen,
4
kTimeoutMs);
Copied!

Disable a limit switch

REV SPARK MAX
Phoenix Framework
1
forwardLimit.EnableLimitSwitch(false);
Copied!
1
talonSRX->OverrideLimitSwitchesEnable(true);
Copied!
Last modified 1mo ago