Search
K

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
import com.revrobotics.CANEncoder;
import com.revrobotics.CANPIDController;
import com.revrobotics.CANSparkMax;
import com.revrobotics.ControlType;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.ctre.phoenix.motorcontrol.can.*;
import com.ctre.phoenix.motorcontrol.*;

Create Object CAN ID 1

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

Reset Factory Defaults

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

Select Encoder

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

Set closed loop constants

REV SPARK MAX
Phoenix Framework
pidController.setP(kP);
pidController.setI(kI);
pidController.setD(kD);
pidController.setIZone(kIz);
pidController.setFF(kFF);
pidController.setOutputRange(kMinOutput, kMaxOutput);
talonSRX.configNominalOutputForward(0, kTimeoutMs);
talonSRX.configNominalOutputReverse(0, kTimeoutMs);
talonSRX.configPeakOutputForward(kMaxOutput, kTimeoutMs);
talonSRX.configPeakOutputReverse(kMinOutput, kTimeoutMs);
talonSRX.config_kF(kPIDLoopIdx, kP, kTimeoutMs);
talonSRX.config_kP(kPIDLoopIdx, kI, kTimeoutMs);
talonSRX.config_kI(kPIDLoopIdx, kD, kTimeoutMs);
talonSRX.config_kD(kPIDLoopIdx, kF, kTimeoutMs);

Run Closed Loop Velocity Control

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

Read RPM of Motor

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

Read Applied Output Percent

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

Run Closed Loop Position Control

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

Change Units from 'rotations' to 'inches'

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

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
pidController.setReference(24.0, ControlType.kPosition);
targetPositionRotations = (M_PI * 4 / 15 * 4096) * 24;
talonSRX.set(ControlMode.Position, targetPositionRotations);

Save Parameters

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

Follow another device

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

Invert a device

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

Configure a limit switch

REV SPARK MAX
Phoenix Framework
forwardLimit = sparkMax.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyOpen);
talonSRX.configForwardLimitSwitchSource(
LimitSwitchSource.LimitSwitchSource_FeedbackConnector,
LimitSwitchNormal.LimitSwitchNormal_NormallyOpen,
kTimeoutMs);

Disable a limit switch

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

C++

Include Library

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

Create Object CAN ID 1

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

Reset Factory Defaults

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

Select Encoder

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

Set closed loop constants

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

Run Closed Loop Velocity Control

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

Read RPM of Motor

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

Read Applied Output Percent

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

Run Closed Loop Position Control

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

Change Units from 'rotations' to 'inches'

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

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
pidController.SetReference(24.0, rev::ControlType::kPosition);
targetPositionRotations = (M_PI * 4 / 15 * 4096) * 24;
talonSRX->Set(ControlMode::Position, targetPositionRotations);

Save Parameters

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

Follow another device

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

Invert a device

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

Configure a limit switch

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

Disable a limit switch

REV SPARK MAX
Phoenix Framework
forwardLimit.EnableLimitSwitch(false);
talonSRX->OverrideLimitSwitchesEnable(true);