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)