Skip to content

Instantly share code, notes, and snippets.

@jhh
Last active February 19, 2018 15:46
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save jhh/41f6a1981aa8243cb44ea2942e963c75 to your computer and use it in GitHub Desktop.
Save jhh/41f6a1981aa8243cb44ea2942e963c75 to your computer and use it in GitHub Desktop.
Example program and output for TalonSRX current limit issue
package org.team2767.thirdcoast;
import com.ctre.phoenix.ErrorCode;
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.Timer;
public class TalonTestRobot extends IterativeRobot {
private TalonSRX talon;
private Timer timer = new Timer();
private double setpoint;
@Override
public void robotInit() {
talon = new TalonSRX(11);
ErrorCode err = talon.configVoltageCompSaturation(12, 10);
check(err);
err = talon.configContinuousCurrentLimit(50, 10);
check(err);
talon.enableCurrentLimit(true);
talon.enableVoltageCompensation(true);
}
@Override
public void teleopInit() {
setpoint = 0.2;
timer.start();
}
@Override
public void teleopPeriodic() {
// reverse Talon every 2 seconds
setpoint *= timer.hasPeriodPassed(2) ? -1 : 1;
talon.set(ControlMode.PercentOutput, setpoint);
}
private void check(ErrorCode code) {
if (code != ErrorCode.OK) {
System.out.println("Talon config error: " + code);
}
}
}
@jhh
Copy link
Author

jhh commented Jan 12, 2018

This test was set up to flip output between +/- 20% every 2 seconds. With current limit disabled we see expected behavior. With current limit enabled at 50 amps we see +/- 100% oscillation for approx 0.8 sec. before reversing.

The motor is turning a unloaded wheel (robot on blocks). Tested on multiple Talons.

To reproduce, compile and run example above with talon.enableCurrentLimit(false); and talon.enableCurrentLimit(true);. TalonSRX is factory reset before each run.

Video: https://youtu.be/E-3qkO6zzYU

With talon.enableCurrentLimit(false);

current_limit_disabled

With talon.enableCurrentLimit(true);

current_limit_enabled

@jhh
Copy link
Author

jhh commented Jan 12, 2018

Screenshots of roboRIO TalonSRX web pages

versions

self_test

@jhh
Copy link
Author

jhh commented Feb 19, 2018

Adding this fixed the problem:

talon.configPeakCurrentDuration(0, 10);

However, a factory reset by itself did not fix the problem. I repeated this a couple of times:

  1. Power-cycle with B/C button pressed - saw flashing green lights as expected.
  2. Ran code without peak disable code, saw issue
  3. Ran code with with peak disable code (as above), fixed issue
  4. Ran code without peak disable code, still ran correctly as expected for persistent setting

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment