Talon SRX and RobotPy

We are trying to get RobotPy set up with our TalonSRXs and we are not having any luck. We know that everything is wired up correctly because we can actuate them through Phoenix Tuner X and we are importing the correct modules (phoenix5) and our code is not reporting any errors in pyfrc_test, however, the Talons simply have the amber lights flashing when we enable the robot. We are using a very basic codebase to get things set up, but without luck. Any help would be greatly appreciated.

#!/usr/bin/env python3
#
# Copyright (c) FIRST and other WPILib contributors.
# Open Source Software; you can modify and/or share it under the terms of
# the WPILib BSD license file in the root directory of this project.
#

import wpilib
import wpilib.drive
import phoenix5


class MyRobot(wpilib.TimedRobot):
    """
    This is a demo program showing the use of the DifferentialDrive class.
    Runs the motors with split arcade steering and an Xbox controller.
    """

    K_P = 1.0
    K_I = 0.0
    K_D = 1.0
    K_F = 0.0

    def initTalon(self, talon, isInverted):
        talon.setSensorPhase(True)
        if (isInverted):
            talon.setInverted(isInverted)
        
        talon.selectProfileSlot(1,0)
        talon.setNeutralMode(phoenix5.NeutralMode.Brake)
        talon.configFactoryDefault()
        talon.configNeutralDeadband(0.01)
        talon.configClosedloopRamp(0)
        
        talon.configSelectedFeedbackSensor(phoenix5.FeedbackDevice.QuadEncoder, 0, 0)
        talon.setSelectedSensorPosition(0, 0, 0)
        talon.configNominalOutputForward(0, 0)
        talon.configNominalOutputReverse(0, 0)
        talon.configPeakOutputForward(1, 0)
        talon.configPeakOutputReverse(-1, 0)

        talon.config_kF(1, self.K_F, 0)
        talon.config_kP(1, self.K_P, 0)
        talon.config_kI(1, self.K_I, 0)
        talon.config_kD(1, self.K_D, 0)

        talon.configClosedloopRamp(0.3)

        return talon

    def robotInit(self):
        """Robot initialization function"""

        '''
        self.config = phoenix5.TalonSRXConfiguration()
        self.config.peakCurrentLimit = 40
        self.config.peakCurrentDuration = 1500
        self.config.continuousCurrentLimit = 30

        print(self.config)
        '''

        # leftMotor = wpilib.PWMSparkMax(0)
        # rightMotor = wpilib.PWMSparkMax(1)
        self.leftMotor1 = self.initTalon(phoenix5.WPI_TalonSRX(4), False)
        self.leftMotor2 = self.initTalon(phoenix5.WPI_TalonSRX(2), False)
        self.rightMotor2 = self.initTalon(phoenix5.WPI_TalonSRX(1), True)
        self.rightMotor1 = self.initTalon(phoenix5.WPI_TalonSRX(3), True)

        print(self.leftMotor1)

        self.leftMotor1.configFactoryDefault()
        self.leftMotor2.configFactoryDefault()
        self.rightMotor2.configFactoryDefault()
        self.rightMotor1.configFactoryDefault()

        '''
        self.leftMotor1.configAllSettings(self.config)
        self.leftMotor2.configAllSettings(self.config)
        self.rightMotor1.configAllSettings(self.config)
        self.rightMotor2.configAllSettings(self.config)
        '''

        self.robotDrive = wpilib.drive.DifferentialDrive(self.leftMotor1, self.rightMotor1)
        self.driverController = wpilib.XboxController(0)

        # We need to invert one side of the drivetrain so that positive voltages
        # result in both sides moving forward. Depending on how your robot's
        # gearbox is constructed, you might have to invert the left side instead.
        self.rightMotor1.setInverted(True)
        self.rightMotor2.setInverted(True)

        print("Init")

    def teleopPeriodic(self):
        # Drive with split arcade style
        # That means that the Y axis of the left stick moves forward
        # and backward, and the X of the right stick turns left and right.
        joyY = -self.driverController.getLeftY()
        joyX = -self.driverController.getRightX()
        # print("Y: ", joyY, "X: ", joyX)
        # print("lm1: ", self.leftMotor1.getOutputCurrent(), "lm2: ", self.leftMotor2.getOutputCurrent(),
        #    "rm1: ", self.rightMotor1.getOutputCurrent(), "rm2: ", self.rightMotor2.getOutputCurrent()
        # )
        self.robotDrive.arcadeDrive(
           joyY , joyX
        )
        # self.leftMotor1.set(phoenix5.TalonSRXControlMode(0), 0.2)
        # self.leftMotor2.set(phoenix5.TalonSRXControlMode(0), 0.2)
        # self.rightMotor1.set(phoenix5.TalonSRXControlMode(0), 0.2)
        # self.rightMotor2.set(phoenix5.TalonSRXControlMode(0), 0.2)

        # print("Teleop")


if __name__ == "__main__":
    wpilib.run(MyRobot)

I’ve heard several reports of this behavior and I don’t have any insight to what’s happening at this time. We’re using CTRE’s libraries in the same way that we have in the past so it should work… but it doesn’t. I’ve reached out to CTRE but they won’t have time to look into it for a few days.

I’ve been told phoenix6 works, but there’s a lot of hardware that CTRE doesn’t support anymore (including the SRX).

That’s really unfortunate. :frowning: We’re also having trouble with getting the CANSparkMax from the rev module working as well. We get the following:

...
>       self.leftMotor = rev.CANSparkMax(1, rev.CANSparkMax.MotorType.kBrushless)
E       AttributeError: module 'rev' has no attribute 'CANSparkMax'
#!/usr/bin/env python3
#
# Copyright (c) FIRST and other WPILib contributors.
# Open Source Software; you can modify and/or share it under the terms of
# the WPILib BSD license file in the root directory of this project.
#

import wpilib
import wpilib.drive
import phoenix5
import rev


class MyRobot(wpilib.TimedRobot):
    """
    This is a demo program showing the use of the DifferentialDrive class.
    Runs the motors with split arcade steering and an Xbox controller.
    """

    K_P = 1.0
    K_I = 0.0
    K_D = 1.0
    K_F = 0.0

    def initTalon(self, talon, isInverted):
        talon.setSensorPhase(True)
        if (isInverted):
            talon.setInverted(isInverted)
        
        talon.selectProfileSlot(1,0)
        talon.setNeutralMode(phoenix5.NeutralMode.Brake)
        talon.configFactoryDefault()
        talon.configNeutralDeadband(0.01)
        talon.configClosedloopRamp(0)
        
        talon.configSelectedFeedbackSensor(phoenix5.FeedbackDevice.QuadEncoder, 0, 0)
        talon.setSelectedSensorPosition(0, 0, 0)
        talon.configNominalOutputForward(0, 0)
        talon.configNominalOutputReverse(0, 0)
        talon.configPeakOutputForward(1, 0)
        talon.configPeakOutputReverse(-1, 0)

        talon.config_kF(1, self.K_F, 0)
        talon.config_kP(1, self.K_P, 0)
        talon.config_kI(1, self.K_I, 0)
        talon.config_kD(1, self.K_D, 0)

        talon.configClosedloopRamp(0.3)

        return talon

    def robotInit(self):
        """Robot initialization function"""

        '''
        self.config = phoenix5.TalonSRXConfiguration()
        self.config.peakCurrentLimit = 40
        self.config.peakCurrentDuration = 1500
        self.config.continuousCurrentLimit = 30

        print(self.config)
        '''

        # leftMotor = wpilib.PWMSparkMax(0)
        # rightMotor = wpilib.PWMSparkMax(1)
        self.leftMotor1 = self.initTalon(phoenix5.WPI_TalonSRX(4), False)
        self.leftMotor2 = self.initTalon(phoenix5.WPI_TalonSRX(2), False)
        self.rightMotor2 = self.initTalon(phoenix5.WPI_TalonSRX(1), True)
        self.rightMotor1 = self.initTalon(phoenix5.WPI_TalonSRX(3), True)

        # self.NEO1 = rev.CANSparkMax(5, rev.CANSparkMax.MotorType.kBrushless)
        self.leftMotor = rev.CANSparkMax(1, rev.CANSparkMax.MotorType.kBrushless)

        print(self.leftMotor1)

        self.leftMotor1.configFactoryDefault()
        self.leftMotor2.configFactoryDefault()
        self.rightMotor2.configFactoryDefault()
        self.rightMotor1.configFactoryDefault()

        '''
        self.leftMotor1.configAllSettings(self.config)
        self.leftMotor2.configAllSettings(self.config)
        self.rightMotor1.configAllSettings(self.config)
        self.rightMotor2.configAllSettings(self.config)
        '''

        self.robotDrive = wpilib.drive.DifferentialDrive(self.leftMotor1, self.rightMotor1)
        self.driverController = wpilib.XboxController(0)

        # We need to invert one side of the drivetrain so that positive voltages
        # result in both sides moving forward. Depending on how your robot's
        # gearbox is constructed, you might have to invert the left side instead.
        self.rightMotor1.setInverted(True)
        self.rightMotor2.setInverted(True)

        print("Init")

    def teleopPeriodic(self):
        # Drive with split arcade style
        # That means that the Y axis of the left stick moves forward
        # and backward, and the X of the right stick turns left and right.
        joyY = -self.driverController.getLeftY()
        joyX = -self.driverController.getRightX()
        # print("Y: ", joyY, "X: ", joyX)
        # print("lm1: ", self.leftMotor1.getOutputCurrent(), "lm2: ", self.leftMotor2.getOutputCurrent(),
        #    "rm1: ", self.rightMotor1.getOutputCurrent(), "rm2: ", self.rightMotor2.getOutputCurrent()
        # )
        self.robotDrive.arcadeDrive(
           joyY , joyX
        )

        self.leftMotor.set(0.5)

        # self.leftMotor1.set(phoenix5.TalonSRXControlMode(0), 0.2)
        # self.leftMotor2.set(phoenix5.TalonSRXControlMode(0), 0.2)
        # self.rightMotor1.set(phoenix5.TalonSRXControlMode(0), 0.2)
        # self.rightMotor2.set(phoenix5.TalonSRXControlMode(0), 0.2)

        # print("Teleop")


if __name__ == "__main__":
    wpilib.run(MyRobot)

I took a look at the CTRE thing and I think I know what’s wrong, should be able to fix it later today.

Which version of robotpy-rev do you have installed? The import is there for me.

$ pip list | grep robotpy-rev
robotpy-rev              2024.2.0

$ python3 -c 'import rev; print(rev.CANSparkMax)'
<class 'rev._rev.CANSparkMax'>

Maybe print out rev.__file__, if it’s not in site-packages do you have a different rev.py file somewhere that is causing issues?

Awesome, thank you for working on this issue!

When I do that it doesn’t show up in the list, however, when I try to install it I get that it is already installed (although not the version that you specify):

PS H:\Desktop\Robotics\Robotics 2023-24\Programming\Python\testpy> py -3 -m pip install robotpy-rev
Requirement already satisfied: robotpy-rev in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (2024.2.0)
Requirement already satisfied: robotpy-wpiutil<2025.0.0,>=2024.1.1 in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (from robotpy-rev) (2024.1.1.1)
Requirement already satisfied: robotpy-wpimath<2025.0.0,>=2024.1.1 in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (from robotpy-rev) (2024.1.1.1)
Requirement already satisfied: wpilib<2025.0.0,>=2024.1.1 in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (from robotpy-rev) (2024.1.1.1)
Requirement already satisfied: robotpy-hal==2024.1.1.1 in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (from wpilib<2025.0.0,>=2024.1.1->robotpy-rev) (2024.1.1.1)
Requirement already satisfied: pyntcore==2024.1.1.1 in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (from wpilib<2025.0.0,>=2024.1.1->robotpy-rev) (2024.1.1.1)
Requirement already satisfied: robotpy-cli~=2024.0b in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (from wpilib<2025.0.0,>=2024.1.1->robotpy-rev) (2024.0.0)
Requirement already satisfied: robotpy-wpinet==2024.1.1.1 in c:\users\dward\appdata\local\programs\python\python312\lib\site-packages (from pyntcore==2024.1.1.1->wpilib<2025.0.0,>=2024.1.1->robotpy-rev) (2024.1.1.1)

It says 2024.2.0 is installed in your log output.

What does py -c 'import rev; print(rev.__file__); print(rev.CANSparkMax)' do?

I spent the entire day on Saturday trying to get our practice robot to spin motors.

Two are Falcons connected to TalonFX controllers, and two were TalonSRXs.

I had the same issue, the Talon SRX blinking lights would stay orange (suggesting no control mode).

Talon FX controllers would every now and then drive the motors. And by every now and then, the code only has a drivetrain, with a default command that takes two joystick inputs and sets the motors. The drivetrain works fine in the simulator, but on the real robot, it was behaving like the Subsystem default command wasn’t even scheduling or executing.

So, with command-based, I couldn’t get Phoenix 5 or 6 to work.

I confirmed that everything is electrically good by actuating both in Tuner X, and also deploying a Java project that is identical.

Our Repo is public.

Whoops, sorry about that. Here is what that command does:

C:\Users\dward\AppData\Local\Programs\Python\Python312\Lib\site-packages\rev\__init__.py
Traceback (most recent call last):
  File "<string>", line 1, in <module>
AttributeError: module 'rev' has no attribute 'CANSparkMax'

@NewtonCrosby , I’m in the same boat. I was just about to check out some Falcons, but perhaps my efforts are moot until this gets resolved. I’m glad that I’m not the only one spinning their wheels on this.

@virtuald , thank you for working on this issue. We really appreciate all of your efforts!

Can you open that file and see what’s in it?

I feel like your install got corrupted somehow. Maybe just pip uninstall robotpy-rev then pip install robotpy-rev?

I think that you might be right. That file was empty. After uninstalling it and then reinstalling it the file now contains this:

from .version import __version__

from . import _init_rev

# autogenerated by 'robotpy-build create-imports rev'
from ._rev import (
    AbsoluteEncoder,
    AnalogInput,
    CANAnalog,
    CANEncoder,
    CANSensor,
    CANSparkBase,
    CANSparkFlex,
    CANSparkLowLevel,
    CANSparkMax,
    CIEColor,
    ColorMatch,
    ColorSensorV3,
    MotorFeedbackSensor,
    REVLibError,
    RelativeEncoder,
    SparkAbsoluteEncoder,
    SparkAnalogSensor,
    SparkFlexExternalEncoder,
    SparkLimitSwitch,
    SparkMaxAbsoluteEncoder,
    SparkMaxAlternateEncoder,
    SparkMaxAnalogSensor,
    SparkMaxLimitSwitch,
    SparkMaxPIDController,
    SparkMaxRelativeEncoder,
  ...
1 Like

pip sucks. That should work now then?

1 Like

I just tried and on the roboRIO itself I get these errors over and over:

 ERROR: importing /home/lvuser/py/robot.py failed! 
 Traceback (most recent call last): 
   File "/usr/local/lib/python3.12/site-packages/robotpy/main.py", line 68, in _load_robot_class 
     spec.loader.exec_module(module) 
   File "<frozen importlib._bootstrap_external>", line 994, in exec_module 
   File "<frozen importlib._bootstrap>", line 488, in _call_with_frames_removed 
   File "/home/lvuser/py/robot.py", line 12, in <module> 
     import rev 
 ModuleNotFoundError: No module named 'rev' 
Warning  0  [phoenix-diagnostics] Server shutdown cleanly. (dur:0)   
Warning  0  [phoenix] Library shutdown cleanly   
Warning  0  [phoenix-diagnostics] Server shutdown cleanly. (dur:0)   
Warning  0  [phoenix] Library shutdown cleanly   



You must add this to your pyproject.toml, and run robotpy sync and robotpy deploy:

requires = [
    "robotpy-rev"
]

I’ve verified that 2024.1.1 of robotpy-ctre allows a TalonSRX to work correctly.

See RobotPy phoenix 5 users should update for upgrade instructions.

1 Like

Interesting. Whilst I saw intermittent enable behaviour from Phoenix 5 Talon FXs, and was unable to enable a Talon SRX, my team’s Talon FXs run fine using Phoenix 6.

Thank you so much! I’ll try it out the next time I’m the lab.

@virtuald , I just had a chance to test out your fixes and Talon SRXs and our Rev Spark Maxs work as well. Thank you so much for getting this fix out so quickly!

1 Like

This topic was automatically closed 365 days after the last reply. New replies are no longer allowed.