Migrating from CTRE Phoenix to SPARK MAX

We're Updating our Documentation! For the most up-to-date information about the SPARK MAX and other ION Motor Controllers please check out the following new documentation pages:

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

import com.revrobotics.CANEncoder;
import com.revrobotics.CANPIDController;
import com.revrobotics.CANSparkMax;
import com.revrobotics.ControlType;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;

Create Object CAN ID 1

private CANSparkMax sparkMax = new CANSparkMax(deviceID, MotorType.kBrushless);

Reset Factory Defaults

sparkMax.restoreFactoryDefaults();

Select Encoder

This is a brushed motor feature and not needed for using brushless motors with SPARK MAX

encoder = sparkMax.getEncoder();
encoder.setInverted(false);
sparkMax.setFeedbackDevice(encoder);

Set closed loop constants

pidController.setP(kP);
pidController.setI(kI);
pidController.setD(kD);
pidController.setIZone(kIz);
pidController.setFF(kFF);
pidController.setOutputRange(kMinOutput, kMaxOutput);

Run Closed Loop Velocity Control

For this example velocity is set at 500 RPM

pidController.setReference(500.0, ControlType.kVelocity);

Read RPM of Motor

encoder.getVelocity();

Read Applied Output Percent

sparkMax.getAppliedOutput();

Run Closed Loop Position Control

This example runs a position control loop for 10 rotations.

pidController.setReference(10.0, ControlType.kPosition);

Change Units from 'rotations' to 'inches'

This example assumes a 4" wheel on a 15:1 reduction

encoder.setPositionFactor(M_PI * 4/15);

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).

pidController.setReference(24.0, ControlType.kPosition);

Save Parameters

// Run after all parameters are set in RobotInit()
sparkMax.burnFlash();

Follow another device

sparkMax1.follow(sparkMax2);

Invert a device

sparkMax.setInverted(true);

Configure a limit switch

forwardLimit = sparkMax.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyOpen);

Disable a limit switch

forwardLimit.EnableLimitSwitch(false);

C++

Include Library

#include "rev/CANSparkMax.h"

Create Object CAN ID 1

rev::CANSparkMax sparkMax{1, rev::CANSparkMax::MotorType::kBrushless};

Reset Factory Defaults

sparkMax.RestoreFactoryDefaults();

Select Encoder

This is a brushed motor feature and not needed for using brushless motors with SPARK MAX.

rev::CANEncoder encoder = sparkMax.GetEncoder(rev::CANEncoder::EncoderType::kQuadrature, 4096);
encoder.SetInverted(true);
sparkMax.SetFeedbackDevice(encoder);

Set closed loop constants

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);

Run Closed Loop Velocity Control

For this example velocity is set at 500 RPM

pidController.SetReference(500.0, rev::ControlType::kVelocity);

Read RPM of Motor

encoder.GetVelocity();

Read Applied Output Percent

sparkMax.GetAppliedOutput();

Run Closed Loop Position Control

This example runs a position control loop for 10 rotations.

pidController.SetReference(10.0, rev::ControlType::kPosition);

Change Units from 'rotations' to 'inches'

This example assumes a 4" wheel on a 15:1 reduction

encoder.SetPositionFactor( M_PI * 4 / 15 );

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).

pidController.SetReference(24.0, rev::ControlType::kPosition);

Save Parameters

// Run after all parameters are set in RobotInit()
sparkMax.BurnFlash();

Follow another device

sparkMax1.Follow(sparkMax2);

Invert a device

sparkMax.SetInverted(true);

Configure a limit switch

rev::CANDigitalInput forwardLimit = sparkMax.GetForwardLimitSwitch(rev::CANDigitalInput::LimitSwitchPolarity::kNormallyOpen);

Disable a limit switch

forwardLimit.EnableLimitSwitch(false);

Last updated