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
  • Summary
  • Including the library and creating a SPARK object
  • Configuring a SPARK
  • Retrieving a configuration parameter from a SPARK
  • Setting status periods

Was this helpful?

Export as PDF
  1. REVLib
  2. REVLib Overview

Migrating to REVLib 2025

PreviousREVLib OverviewNextClosed-Loop Control Overview

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!

Only SPARK MAX and SPARK Flex are affected by the REVLib 2025 release. Color Sensor V3 is unaffected.

Summary

The 2025 version of REVLib introduced a series of breaking changes from the previous year. These changes include:

  • An overhauled configuration system

  • Updated import paths

  • Renamed classes

For a more complete changelog, please see our on GitHub.

Below shows how to migrate certain common tasks from previous versions of REVLib to the 2025 release.

Including the library and creating a SPARK object

In the 2025 version, all SPARK related classes moved to a spark package in Java and a spark namespace in C++.

In addition, some of the classes were renamed:

  • CANSparkMax is now SparkMax

  • CANSparkFlex is now SparkFlex

  • CANSparkLowLevel is now SparkLowLevel

  • SparkPIDController is now SparkClosedLoopController

Before

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.SparkPIDController;

CANSparkMax max = new CANSparkMax(1, MotorType.kBrushless);
CANSparkFlex flex = new CANSparkFlex(2, MotorType.kBrushless);
SparkPIDController maxPid = max.getPIDController();

After

import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkFlex;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkClosedLoopController;

SparkMax max = new SparkMax(1, MotorType.kBrushless);
SparkFlex flex = new SparkFlex(2, MotorType.kBrushless);
SparkClosedLoopController maxPid = max.getClosedLoopController();

Before

#include <rev/CANSparkMax.h>
#include <rev/CANSparkFlex.h>

using namespace rev;

CANSparkMax m_max{1, CANSparkMax::MotorType::kBrushless};
CANSparkFlex m_flex{2, CANSparkFlex::MotorType::kBrushless};
SparkPIDController m_maxPid = m_max.GetPIDController();

After

#include <rev/SparkMax.h>
#include <rev/SparkFlex.h>

using namespace rev::spark;

SparkMax m_max{1, SparkMax::MotorType::kBrushless};
SparkFlex m_flex{2, SparkFlex::MotorType::kBrushless};
SparkClosedLoopController m_maxPid = m_max.GetClosedLoopController();

Configuring a SPARK

Instead of imperatively configuring parameters of the SPARK by calling methods directly on it and its auxiliary objects (sensors, closed loop controller, etc.), configuration parameters are set in a more declarative way through configuration objects and applying that configuration to the SPARK.

A more complete guide on the new configuration system will soon be available.

For simplicity, only an example for SPARK MAX is provided. The following will still be valid for a SPARK Flex object.

Before

CANSparkMax max = new CANSparkMax(1, MotorType.kBrushless);
RelativeEncoder enc = max.getEncoder();
SparkPIDController pid = max.getPIDController();

max.restoreFactoryDefaults();

max.setInverted(true);
max.setIdleMode(IdleMode.kBrake);
enc.setPositionConversionFactor(1000);
enc.setVelocityConversionFactor(1000);
pid.setFeedbackDevice(enc);
pid.setP(1.0);
pid.setI(0.0);
pid.setD(0.0);

max.burnFlash();

After

SparkMax max = new SparkMax(1, MotorType.kBrushless);
SparkMaxConfig config = new SparkMaxConfig();

config
    .inverted(true)
    .idleMode(IdleMode.kBrake);
config.encoder
    .positionConversionFactor(1000)
    .velocityConversionFactor(1000);
config.closedLoop
    .feedbackSensor(FeedbackSensor.kPrimaryEncoder)
    .pid(1.0, 0.0, 0.0);
    
max.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);

Before

using namespace rev;

CANSparkMax m_max{1, MotorType.kBrushless};
SparkRelativeEncoder m_enc = m_max.GetEncoder();
SparkPIDController m_pid = m_max.GetPIDController();

m_max.RestoreFactoryDefaults();

m_max.SetInverted(true);
m_max.SetIdleMode(IdleMode.kBrake);
m_enc.SetPositionConversionFactor(1000);
m_enc.SetVelocityConversionFactor(1000);
m_pid.SetFeedbackDevice(enc);
m_pid.SetP(1.0);
m_pid.SetI(0.0);
m_pid.SetD(0.0);

m_max.BurnFlash();

After

using namespace rev::spark;

SparkMax m_max{1, SparkMax::MotorType::kBrushless};
SparkMaxConfig config{};

config
    .Inverted(true)
    .SetIdleMode(SparkMaxConfig::IdleMode::kBrake);
config.encoder
    .PositionConversionFactor(1000)
    .VelocityConversionFactor(1000);
config.closedLoop
    .SetFeedbackSensor(ClosedLoopConfig::FeedbackSensor::kPrimaryEncoder)
    .Pid(1.0, 0.0, 0.0);
    
m_max.Configure(config, SparkMax::ResetMode::kResetSafeParameters, SparkMax::PersistMode::kPersistParameters);

Retrieving a configuration parameter from a SPARK

With the new configuration system, parameter getters moved to a configAccessor field in the SparkMax and SparkFlex.

For simplicity, only an example for SPARK MAX is provided. The following will still be valid for a SPARK Flex object.

Before

CANSparkMax max = new CANSparkMax(1, MotorType.kBrushless);
RelativeEncoder enc = max.getEncoder();

boolean isInverted = max.getInverted();
double positionConversionFactor = enc.getPositionConversionFactor();
double velocityConversionFactor = enc.getVelocityConversionFactor();

After

SparkMax max = new SparkMax(1, MotorType.kBrushless);

boolean isInverted = max.configAccessor.getInverted();
double positionFactor = max.configAccessor.encoder.getPositionConversionFactor();
double velocityFactor = max.configAccessor.encoder.getVelocityConversionFactor();

Before

using namespace rev;

CANSparkMax m_max{1, CANSparkMax::MotorType::kBrushless};
SparkRelativeEncoder m_enc = m_max.GetEncoder();

bool isInverted = m_max.GetInverted();
double positionFactor = m_enc.GetPositionConversionFactor();
double velocityFactor = m_enc.GetVelocityConversionFactor();

After

using namespace rev::spark;

SparkMax m_max{1, SparkMax::MotorType::kBrushless};

bool isInverted = m_max.configAccessor.GetInverted();
double positionFactor = m_max.configAccessor.encoder.GetPositionConversionFactor();
double velocityFactor = m_max.configAccessor.encoder.GetVelocityConversionFactor();

Setting status periods

Previously, setting status periods required the user to know which periodic status frame a signal belonged to. Now, status signals' periods can be individually configured, and REVLib will handle figuring out which status frame to adjust.

These values can be configured through the new configuration system.

For simplicity, only an example for SPARK MAX is provided. The following will still be valid for a SPARK Flex object.

Before

CANSparkMax max = new CANSparkMax(1, MotorType.kBrushless);

max.restoreFactoryDefaults();
// Adjust periodic status frame 2, which includes encoder position data
max.setPeriodicFramePeriod(PeriodicFrame.kStatus2, 5);
max.burnFlash();

double position = max.getEncoder().getPosition();

After

SparkMax max = new SparkMax(1, MotorType.kBrushless);
SparkMaxConfig config = new SparkMaxConfig();

config.signals.primaryEncoderPositionPeriodMs(5);

max.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);

double position = max.getEncoder().getPosition();

Before

using namespace rev;

CANSparkMax m_max{1, MotorType.kBrushless};

m_max.RestoreFactoryDefaults();
// Adjust periodic status frame 2, which includes encoder position data
m_max.SetPeriodicFramePeriod(CANSparkMax::PeriodicFrame::kStatus2, 5);
m_max.BurnFlash();

double position = m_max.GetEncoder().GetPosition();

After

using namespace rev::spark;

SparkMax m_max{1, SparkMax::MotorType::kBrushless};
SparkMaxConfig config{};

config.signals.PrimaryEncoderPositionPeriodMs(5);
    
m_max.Configure(config, SparkMax::ResetMode::kResetSafeParameters, SparkMax::PersistMode::kPersistParameters);

double position = m_max.GetEncoder().GetPosition();

https://docs.revrobotics.com/revlib
2025 beta release notes