LogoLogo
REVLib Docs
  • REV ION Brushless
  • Quick Links
  • Frequently Asked Questions
  • NEO Brushless Motors
    • Brushless DC Motor Basics
    • NEO Vortex
      • Docking a SPARK Flex
      • Vortex Shafts
      • Installing a Shaft
      • NEO Vortex Solo Adapter
    • NEO V1.1
      • NEO V1
      • Pinion Pressing Guides
    • NEO 550
      • Pinion Pressing Guide
    • Dynamometer Testing
    • Motor Comparison
  • SPARK Flex Motor Controller
    • SPARK Flex Overview
      • SPARK Flex Dock
    • SPARK Flex Specifications
    • SPARK Flex Feature Description
      • Power and Motor Connections
      • Control Connections
      • Data Port
      • Mounting Holes
      • Control Interfaces
      • Mode Button
      • Operating Modes
    • SPARK Flex Getting Started
      • Wiring the SPARK Flex
      • Make it Spin!
      • Basic Configurations
    • SPARK Flex Status LED Patterns
    • SPARK Flex Troubleshooting
    • SPARK Flex Operating Modes
  • SPARK MAX Motor Controller
    • SPARK MAX Overview
    • SPARK MAX Specifications
      • Power and Motor Connections
      • Control Connections
      • Encoder Port
      • Data Port
    • SPARK MAX Getting Started
      • Wiring the SPARK MAX
      • Make it Spin!
      • Basic Configurations
    • SPARK MAX Status LED Patterns
    • SPARK MAX Troubleshooting
    • SPARK MAX Operating Modes
    • SPARK MAX Control Interfaces
    • SPARK MAX Configuration Parameters
    • Using Encoders with the SPARK MAX
      • Absolute Encoders
      • Alternate Encoder Mode
      • Securing the Encoder Adapters
      • Calibration for MAXSwerve
  • REVLib
    • REVLib Overview
      • REVLib Changelog
      • Migrating to REVLib 2025
    • Closed-Loop Control Overview
      • Closed Loop Control Getting Started
      • Getting Started with PID Tuning
      • Position Control Mode
      • Velocity Control Mode
      • Current Control Mode
      • Smart Motion Control
      • Smart Velocity Control
    • Code Examples
    • Migrating to REVLib
    • Device Firmware Changelogs
  • Tips and Tricks
    • Anderson Powerpole Connectors
    • REV Hardware Client Documentation
  • Legacy Documentation
    • SPARK Motor Controller
    • SPARK MAX Client
      • Navigating the SPARK MAX Client
      • Updating Device Firmware
      • Recovery Mode with the SPARK MAX Client
      • SPARK MAX Client Troubleshooting
Powered by GitBook
On this page
  • Migrating from the SPARK MAX API and/or Color Sensor V3 API
  • Migrating from CTRE Phoenix
  • Migrating from CTRE Phoenix: Java
  • Include Library
  • Create Object CAN ID 1
  • Reset Factory Defaults
  • Select Encoder
  • Set closed loop constants
  • Run Closed Loop Velocity Control
  • Read RPM of Motor
  • Read Applied Output Percent
  • Run Closed Loop Position Control
  • Change Units from 'rotations' to 'inches'
  • Run Closed Loop Position Control for a set distance
  • Save Parameters
  • Follow another device
  • Invert a device
  • Configure a limit switch
  • Disable a limit switch
  • Migrating from CTRE Phoenix: C++
  • Include Library
  • Create Object CAN ID 1
  • Reset Factory Defaults
  • Select Encoder
  • Set closed loop constants
  • Run Closed Loop Velocity Control
  • Read RPM of Motor
  • Read Applied Output Percent
  • Run Closed Loop Position Control
  • Change Units from 'rotations' to 'inches'
  • Run Closed Loop Position Control for a set distance
  • Save Parameters
  • Follow another device
  • Invert a device
  • Configure a limit switch
  • Disable a limit switch

Was this helpful?

Export as PDF
  1. REVLib

Migrating to REVLib

PreviousCode ExamplesNextDevice Firmware Changelogs

Last updated 4 months ago

Was this helpful?

January 4, 2025 Update -

Documentation for REVLib 2025 can now be found at:

Please bookmark our new page as we transition over and add more information there!

Migrating from the SPARK MAX API and/or Color Sensor V3 API

Beginning in 2022, The SPARK MAX API and the Color Sensor V3 API have been merged into a unified library called REVLib. You need to make sure that you have uninstalled those old libraries before you install REVLib.

LabVIEW migration

  1. Ensure that the old SPARK MAX API and/or Color Sensor V3 API packages are uninstalled.

  2. .

  3. Opening a project that used the old APIs should work fine. When it is loading, it may show that there are some missing VIs, but eventually LabVIEW should find the new VIs automatically.

C++/Java migration

  1. Open your robot project in VSCode.

  2. Click on the WPI icon in the corner to open the WPI Command Pallet.

  3. Select Manage Vendor Libraries.

  4. Select Manage Current Libraries.

  5. Check the REVRobotics and/or REVColorSensorV3 items (whichever ones are present)

  6. Click the OK button to uninstall them.

  7. Install REVLib for .

Migrating from CTRE Phoenix

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.

Migrating from CTRE Phoenix: Java

Include Library

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

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

Reset Factory Defaults

sparkMax.restoreFactoryDefaults();
talonSRX.configFactoryDefault();

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);
talonSRX.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, kPIDLoopIdx, Constants.kTimeoutMs);
talonSRX.setSensorPhase(true);

Set closed loop constants

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

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

encoder.getVelocity();
talonSRX.getSelectedSensorVelocity(kPIDLoopIdx) * 600 / 4096;

Read Applied Output Percent

sparkMax.getAppliedOutput();
talonSRX.getMotorOutputPercent();

Run Closed Loop Position Control

This example runs a position control loop for 10 rotations.

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

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

pidController.setReference(24.0, ControlType.kPosition);
targetPositionRotations = (M_PI * 4 / 15 * 4096) * 24;
talonSRX.set(ControlMode.Position, targetPositionRotations);

Save Parameters

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

Follow another device

sparkMax1.follow(sparkMax2);
talonSRX1.follow(talonSRX2);

Invert a device

sparkMax.setInverted(true);
talonSRX.setInverted(true);

Configure a limit switch

forwardLimit = sparkMax.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyOpen);
talonSRX.configForwardLimitSwitchSource(
                                        LimitSwitchSource.LimitSwitchSource_FeedbackConnector,
                                        LimitSwitchNormal.LimitSwitchNormal_NormallyOpen,
                                        kTimeoutMs);

Disable a limit switch

forwardLimit.EnableLimitSwitch(false);
talonSRX.overrideLimitSwitchesEnable(true);

Migrating from CTRE Phoenix: C++

Include Library

#include "rev/CANSparkMax.h"
#include "ctre/Phoenix.h"

Create Object CAN ID 1

rev::CANSparkMax sparkMax{1, rev::CANSparkMax::MotorType::kBrushless};
TalonSRX* talon = new TalonSRX(1);

Reset Factory Defaults

sparkMax.RestoreFactoryDefaults();
talon->ConfigFactoryDefault();

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);
talonSRX->ConfigSelectedFeedbackSensor(FeedbackDevice::CTRE_MagEncoder_Relative, 0, kTimeoutMs);
talonSRX->SetSensorPhase(true);

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

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

encoder.GetVelocity();
talonSRX->GetSelectedSensorVelocity(kPIDLoopIdx) * 600 / 4096;

Read Applied Output Percent

sparkMax.GetAppliedOutput();
talonSRX->GetMotorOutputPercent();

Run Closed Loop Position Control

This example runs a position control loop for 10 rotations.

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

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

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

Save Parameters

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

Follow another device

sparkMax1.Follow(sparkMax2);
talonSRX1->Follow(*talon2);

Invert a device

sparkMax.SetInverted(true);
talonSRX->SetInverted(true);

Configure a limit switch

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

Disable a limit switch

forwardLimit.EnableLimitSwitch(false);
talonSRX->OverrideLimitSwitchesEnable(true);
https://docs.revrobotics.com/revlib
Install the REVLib package
C++ and Java