Migrating to REVLib 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
Ensure that the old SPARK MAX API and/or Color Sensor V3 API packages are uninstalled.
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
Open your robot project in VSCode.
Click on the WPI icon in the corner to open the WPI Command Pallet.
Select Manage Vendor Libraries .
Select Manage Current Libraries .
Check the REVRobotics
and/or REVColorSensorV3
items (whichever ones are present)
Click the OK
button to uninstall them.
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
REV SPARK MAX
Copy import com . revrobotics . CANEncoder ;
import com . revrobotics . CANPIDController ;
import com . revrobotics . CANSparkMax ;
import com . revrobotics . ControlType ;
import com . revrobotics . CANSparkMaxLowLevel . MotorType ;
Phoenix Framework
Copy import com . ctre . phoenix . motorcontrol . can . * ;
import com . ctre . phoenix . motorcontrol . * ;
Create Object CAN ID 1
REV SPARK MAX
Copy private CANSparkMax sparkMax = new CANSparkMax(deviceID , MotorType . kBrushless ) ;
Phoenix Framework
Copy TalonSRX talonSRX = new TalonSRX(1);
Reset Factory Defaults
REV SPARK MAX
Copy sparkMax . restoreFactoryDefaults ();
Phoenix Framework
Copy talonSRX.configFactoryDefault();
Select Encoder
This is a brushed motor feature and not needed for using brushless motors with SPARK MAX
REV SPARK MAX
Copy encoder = sparkMax . getEncoder ();
encoder . setInverted ( false );
sparkMax . setFeedbackDevice (encoder);
Phoenix Framework
Copy talonSRX . configSelectedFeedbackSensor ( FeedbackDevice . CTRE_MagEncoder_Relative , kPIDLoopIdx , Constants . kTimeoutMs);
talonSRX . setSensorPhase ( true );
Set closed loop constants
REV SPARK MAX
Copy pidController . setP (kP);
pidController . setI (kI);
pidController . setD (kD);
pidController . setIZone (kIz);
pidController . setFF (kFF);
pidController . setOutputRange (kMinOutput , kMaxOutput);
Phoenix Framework
Copy 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
Copy pidController . setReference ( 500.0 , ControlType . kVelocity );
Phoenix Framework
Copy // 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
Copy encoder . getVelocity ();
Phoenix Framework
Copy talonSRX . getSelectedSensorVelocity (kPIDLoopIdx) * 600 / 4096 ;
Read Applied Output Percent
REV SPARK MAX
Copy sparkMax . getAppliedOutput ();
Phoenix Framework
Copy talonSRX . getMotorOutputPercent ();
Run Closed Loop Position Control
This example runs a position control loop for 10 rotations.
REV SPARK MAX
Copy pidController . setReference ( 10.0 , ControlType . kPosition );
Phoenix Framework
Copy 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
Copy 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).
REV SPARK MAX
Copy pidController . setReference ( 24.0 , ControlType . kPosition );
Phoenix Framework
Copy targetPositionRotations = (M_PI * 4 / 15 * 4096 ) * 24 ;
talonSRX . set ( ControlMode . Position , targetPositionRotations);
Save Parameters
REV SPARK MAX
Copy // Run after all parameters are set in RobotInit()
sparkMax . burnFlash ();
Follow another device
REV SPARK MAX
Copy sparkMax1 . follow (sparkMax2);
Phoenix Framework
Copy talonSRX1 . follow (talonSRX2);
Invert a device
REV SPARK MAX
Copy sparkMax . setInverted ( true );
Phoenix Framework
Copy talonSRX.setInverted(true);
Configure a limit switch
REV SPARK MAX
Copy forwardLimit = sparkMax . getForwardLimitSwitch ( LimitSwitchPolarity . kNormallyOpen );
Phoenix Framework
Copy talonSRX . configForwardLimitSwitchSource (
LimitSwitchSource . LimitSwitchSource_FeedbackConnector ,
LimitSwitchNormal . LimitSwitchNormal_NormallyOpen ,
kTimeoutMs);
Disable a limit switch
REV SPARK MAX
Copy forwardLimit . EnableLimitSwitch ( false );
Phoenix Framework
Copy talonSRX . overrideLimitSwitchesEnable ( true );
Migrating from CTRE Phoenix: C++
Include Library
REV SPARK MAX
Copy #include "rev/CANSparkMax.h"
Phoenix Framework
Copy #include "ctre/Phoenix.h"
Create Object CAN ID 1
REV SPARK MAX
Copy rev :: CANSparkMax sparkMax{ 1 , rev :: CANSparkMax :: MotorType :: kBrushless};
Phoenix Framework
Copy TalonSRX * talon = new TalonSRX ( 1 );
Reset Factory Defaults
REV SPARK MAX
Copy sparkMax . RestoreFactoryDefaults ();
Phoenix Framework
Copy talon -> ConfigFactoryDefault ();
Select Encoder
This is a brushed motor feature and not needed for using brushless motors with SPARK MAX.
REV SPARK MAX
Copy rev ::CANEncoder encoder = sparkMax . GetEncoder (rev :: CANEncoder :: EncoderType :: kQuadrature , 4096 );
encoder . SetInverted ( true );
sparkMax . SetFeedbackDevice (encoder);
Phoenix Framework
Copy talonSRX -> ConfigSelectedFeedbackSensor (FeedbackDevice :: CTRE_MagEncoder_Relative , 0 , kTimeoutMs);
talonSRX -> SetSensorPhase ( true );
Set closed loop constants
REV SPARK MAX
Copy 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);
Phoenix Framework
Copy 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
Copy pidController . SetReference ( 500.0 , rev :: ControlType :: kVelocity);
Phoenix Framework
Copy "// 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
Copy encoder . GetVelocity ();
Phoenix Framework
Copy talonSRX -> GetSelectedSensorVelocity(kPIDLoopIdx) * 600 / 4096 ;
Read Applied Output Percent
REV SPARK MAX
Copy sparkMax . GetAppliedOutput ();
Phoenix Framework
Copy talonSRX -> GetMotorOutputPercent() ;
Run Closed Loop Position Control
This example runs a position control loop for 10 rotations.
REV SPARK MAX
Copy pidController . SetReference ( 10.0 , rev :: ControlType :: kPosition);
Phoenix Framework
Copy 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
Copy 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).
REV SPARK MAX
Copy pidController . SetReference ( 24.0 , rev :: ControlType :: kPosition);
Phoenix Framework
Copy targetPositionRotations = (M_PI * 4 / 15 * 4096 ) * 24 ;
talonSRX -> Set(ControlMode :: Position , targetPositionRotations) ;
Save Parameters
REV SPARK MAX
Copy // Run after all parameters are set in RobotInit()
sparkMax . BurnFlash ();
Follow another device
REV SPARK MAX
Copy sparkMax1 . Follow (sparkMax2);
Phoenix Framework
Copy talonSRX1 -> Follow( * talon2) ;
Invert a device
REV SPARK MAX
Copy sparkMax . SetInverted ( true );
Phoenix Framework
Copy talonSRX -> SetInverted ( true );
Configure a limit switch
REV SPARK MAX
Copy rev ::CANDigitalInput forwardLimit = sparkMax . GetForwardLimitSwitch (rev :: CANDigitalInput :: LimitSwitchPolarity :: kNormallyOpen);
Phoenix Framework
Copy talonSRX -> ConfigForwardLimitSwitchSource(
LimitSwitchSource :: LimitSwitchSource_FeedbackConnector ,
LimitSwitchNormal :: LimitSwitchNormal_NormallyOpen ,
kTimeoutMs) ;
Disable a limit switch
REV SPARK MAX
Copy forwardLimit . EnableLimitSwitch ( false );
Phoenix Framework
Copy talonSRX -> OverrideLimitSwitchesEnable( true ) ;