Talon SRX PIDF velocity tuning

In tuning our shooter motor (dual 775 pro, two Talon SRX, one in follow mode, Vex encoder wired directly to the controller) I’ve read many posts, and the CTR manual, and I’m struggling to understand the odd behavior.

I’ve used the Talons before for position PID (elevator) and it worked great. It’s also intuitive: Start at all zeros, tune P until the elevator rapidly reaches the target position and oscillates around it. Reduce P as much as you can to remove oscillation without sacrificing speed, add some D to soften the landing and eliminate any remaining oscillation, and use a tiny bit of I if there’s error preventing you from getting close enough to the target. It all makes sense.

Velocity tuning, on the other hand is giving me fits. According to the instructions, I should start with the Feedback F term, which, if it’s large enough, should cause the velocity to oscillate around the target rate. But no matter how I set it, it always smoothly approaches a value as an asymptote and then stays there. But the value that it stabilizes on varies depending on the value of F. Why? The target value is the encoder speed. That’s a known quantity. If I’m requesting 50000 encoder ticks per second, why would it stabilize on 65000, or 60000, depending on the value of F? Shouldn’t that value determine how fast or slow it reaches the target, and therefore how much it will oscillate around it when it overshoots?

To elaborate a little: Obviously, with tuning, I’ve been able to reach a target velocity, only by fudging the actual velocity I’m asking for. I’d really like it to hit the target I’m asking for, and shouldn’t I be able to ask it for multiple targets?

In particular, we’re using a fixed-angle shooter for the sake of simplicity, and varying the shoot speed in order to go between high goals and low goals. And this is the problem. I can find a value of F that will reliably get me to 60000 ticks/sec when I ask for 60000, but if I ask for 20000 it falls far short. If I re-tune F, I can hit 20000 perfectly, and then 60000 way overshoots.

I’ve experimenting with tuning P, but so far that’s only adding tiny oscillations around the wrong value! Worse still, adding any I term, even a very tiny one, results in runaway acceleration. Experimenting with the D term results in the target lowering, but again, it’s asymmetrically hitting target values inaccurately.

The main thing I’m trying to avoid is this: I do not want to stabilize around a different target value depending on the charge level of the battery! And yet, that’s exactly what’s happening. That’s not good.

This is a very naive tuning approach that “works” but does not really attempt to approximate optimal control. It works for position because position control generally occurs over relatively long timescales and is subject to fewer forces (a stationary motor stays where it is without any driving voltage unless something else acts on it).

To start, you have to understand that velocity control and position control are different things that behave differently. In the position case above, a stationary motor doesn’t require a driving signal to stay on-target. A moving motor, however, does - so if we try to control it purely with a feedback strategy whose output disappears at zero error, we’re not likely to succeed.

To make it work, you have to take into account some knowledge of how the system works, and use that knowledge to make a guess as to the driving voltage required to maintain the state you want. This is called “feedforward.”

This is incorrect on multiple levels. The F gain is a feedforward gain, not a feedback gain, and is multiplied by the setpoint (in the Talon’s bonkers internal units of sensor ticks per 100ms). If you set the value of F correctly, this will correctly account for the back-EMF of the motor, which is one of those forces that you have to cancel out to make this control strategy work (other forces may include friction and/or the inertia of the robot).

For most velocity control scenarios this feedforward strategy is enough to work acceptably when combined with feedback, but it is not part of the feedback controller, and better results can usually be obtained by using a more-accurate feedforward (check out the WPILib feedforward classes).

This is exactly what you should expect it to do - a F-only control loop is an open control loop, and is equivalent to giving the motor a percentage of max voltage corresponding to the fraction of its nominal free speed that you want it to go.

The job of the feedback controller is to correct any residual errors from your feedforward model. If your feedforward is decently accurate, you should generally only need a P gain for velocity control.

If your feedforward is inaccurate, the proportional gain will not be able to drive the velocity very close to the setpoint because it will have to fight against the back-EMF of the motor.

Naive integral gain is almost always a bad idea - it has infinite memory, and basically functions as a maximally-ignorant bias estimator. You can hack around this with “integrator zone” settings and whatnot, but it’s still trying to put in a screw with a hammer.

Derivative gain is useless for velocity control unless the setpoint is moving.

2 Likes

Man, my brain is fried. I meant Feedforward and just typed the opposite thing off the top of my head. But thanks for the help. I hope you don’t mind if I try to get a deeper understanding here:

This is the part that’s confusing me a bit. Or maybe I’m overthinking it. Are you saying that basically when I specify a Feedforward term and the PID are all zeros, and I request a target velocity, essentially what’s happening is that the Talon is just doing the math to calculate what the voltage output should be for that requested target velocity? So it’s almost identical to specifying set(ControlMode.PercentOutput, value) with a pre-calculated value?

This is what I was assuming, but this is definitely where I get confused by the results I’m seeing. In the Phoenix Tuner, if I specify a P term, I can see it making a difference, and in particular I can start to see oscillations in the measured velocity. However, it’s oscillating around the wrong value. If the current velocity is higher than the target I’ve provided, shouldn’t the P term cause it to slow down by reducing the power? Why would it ever provide MORE power when it’s already above the target? Or is there a limit to how much error it can account for?

One more quick question, and I really appreciate your patience: What is the best way to determine the “free speed” of the motor at 100% power output in order to calculate the F term as accurately as possible? Use the tuner to take encoder speed measurements while I run the motor at 100 power? Should that measurement be done under load, or should I unhook the shooter belt and take a measurement with no load? My instinct is to do it under load, but I’ve been wrong about so many things I’m second-guessing everything at this point.

Yes, this is exactly what I’m saying.

If you’re above the target velocity and your P term is making your loop go faster, then you have a sign error somewhere in your measurements - the feedback is supposed to oppose the current error.

The reason you will see a P-only loop oscillate around the wrong setpoint is because it is oscillating around the equilibrium point between the control effort of the feedback loop and the back-EMF of the motor. Increasing P will drive the center of the oscillation closer to the setpoint, at the cost of making it oscillate more.

Ideally, your feedforward will be accurate enough that you can use a stable P gain while maintaining acceptable steady-state error.

You should always characterize your systems under load, because it’s their performance under load that you’re trying to control. WPILib ships with a system identification toolsuite that can help with this.

You can also get estimated feedforward terms from ReCalc. Note that these will be in terms of the surface speed of the shooter, not the angular speed, and you’ll have to do some conversion to the calculated kV to put it in the same units as the Talon’s F gain (alternatively, use a WPILib feedforward object and pass the calculated feedforward voltage in as a percent output through the Talon’s arbitrary feedforward parameter).

This is something that I overlooked the first time we tuned a shooter velocity pid as well, there’s a little nugget in the closed-loop control docs from CTRE.
From the CTRE

This should explain plainly why you see the result scaling with kF (even if counterintuitively to you at the time).

Oblarg’s explanations should be sufficient enough to help you understand how this kF multiplication of the target velocity is an open-loop control, roughly a percent output.

Update: The revelation of FeedForward being basically a scaled open loop percent output was definitely the key misunderstanding, and everything’s working beautifully now.

As you suspected, I did in fact have a sign error! I needed to tell the Talon to invert the sensor value. The whole reason I didn’t think it was inverted was that velocity command was spinning the motor in the correct direction with only an F term; I assumed that F and P were both going to be interpreting the sensor in the same way. The fact that F doesn’t care about the sensor at all suddenly made everything make sense.

Proper F calculations according to the CTR manual got me the right power profile, and tuning the P term got me an extremely rapid acceleration to the target velocity with minimal oscillation according to the phoenix tuner velocity plot. We’re now hitting shooting speed smoothly, consistently and in < 0.5 seconds. I used the same principles on the intake and index motors (with appropriate math for the gearing.) Velocity control even helps those systems with all the variable friction/compression/etc. to make everything nice and predictable (along with the Talon’s handy multi-profile configuration so that when the intake/index is supposed to stop, I can switch to Position control, reset the sensor position to 0 and set target position to 0 when stopping, which holds the cargo in place much more firmly than merely using neutral braking mode.)

Thanks so much for the advice and clarification!

1 Like

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