View Single Post
  #9   Spotlight this post!  
Unread 15-06-2016, 01:54
AustinSchuh AustinSchuh is offline
Registered User
FRC #0971 (Spartan Robotics) #254 (The Cheesy Poofs)
Team Role: Engineer
 
Join Date: Feb 2005
Rookie Year: 1999
Location: Los Altos, CA
Posts: 803
AustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond reputeAustinSchuh has a reputation beyond repute
Re: FRC971 Spartan Robotics 2016 Release Video

Quote:
Originally Posted by ranlevinstein View Post
First of all your robot is truly amazing!

I have a few questions about your control.

1.I have read about your delta-u controller and I am not sure if I understood it correctly and I would like to know if i got it right. You have 3 states on your state space controller which include position , velocity and error voltage. you model it as (dx/dt) = Ax + Bu and u is the rate of change of voltage. Then you use pole placement to find the K matrix and then in your controller you set u to be -Kx. Then you estimate the state from position using an observer. you use an integrator for u and command the motors with it. To the error voltage state you feed in the difference between the estimated voltage from the observer and the integrated u commands.

2.Will the delta-u controller work the same if i will command the motors with u and not the integral of it and instead use the integral voltage error as state? why did you choose this way for the controller and not another form?
You nailed it.

Delta-U won't work if you command the motors with U, since your model doesn't match your plant (off by an integral).

I've recently switched formulations to what we used this and last year, and I think the new formulation is easier to understand.

If you have an un-augmented plant dx/dt = Ax + Bu, you can augment it by adding a "voltage error state".

d[x; voltage_error]/dt = [A, B; 0, 0] x + [B; 0] u

You then design the controller to control the original Ax + Bu (u =K * (R - X), design an observer to observe the augmented X, and then use a controller which is really [K, 1].

We switched over last year because it was easier to think about the new controller. In the end, both it and Delta U controllers will do the same thing.

Quote:
Originally Posted by ranlevinstein View Post
3.Is the delta-u controller in the end a linear combination of position error, velocity error and voltage error?
Yes. It's just another way to add integral into the mix. I like it because if your model is performing correctly, you won't get any integral windup. The trick is that it lets the applied voltage diverge from the voltage that the robot appears to be moving with by observing it in the observer.

Quote:
Originally Posted by ranlevinstein View Post
4.Why did you use Kalman filter instead of a regular observer? How much better was it in comparison to a regular observer?
It's just another way to tune a state space observer. If you check the math, if you assume fixed gains, the kalman gain converges to a fixed number as time evolves. You can solve for that kalman gain and use it all the time. Which results in the update step you find in an observer.

Honestly, I end up tuning it one way and then looking at the poles directly at the end to see how the tuning affected the results.

Quote:
Originally Posted by ranlevinstein View Post
5.How did you tune the Q and R matrices in the kalman filter?
The rule of thumb I've been using is to set the diagonal terms to the square of a reasonable error quantity for that term (for Q), and try to guess how much model uncertainty there is. I also like to look at the resulting kalman gain to see how crazy it is, and then also plot the input vs the output of the filter and look at how well it performs during robot moves. I've found that if I look at things from enough angles, I get a better picture of what's going on.

Quote:
Originally Posted by ranlevinstein View Post
6.How do you tune the parameters that transfrom the motion profile to the feed-forward you can feed to your motors?
I didn't. I defined a cost function to minimize the error between the trajectory every cycle and a feed-forward based goal (this made the goal feasabile), and used that to define a Kff.

The equation to minimize is:

(B * U - (R(n+1) - A R(n)))^T * Q * (B * U - (R(n+1) - A R(n)))

This means that you have 3 goals running around. The un-profiled goal, the profiled goal and the R that the feed-forwards is asking you to go to. I'd recommend you read the code to see how we kept track of it all, and I'm happy to answer questions from there.

The end result was that our model defined the feed-forwards constants, so it was free We also were able to gain schedule the feed-forwards terms for free as well.

FYI, this was the first year that we did feed-forwards. Before, we just relied on the controllers compensating. You can see it in some of the moves in the 2015 robot where it'll try to do a horizontal move, but end up with a steady state offset while moving due to the lack of feed-forwards.

Quote:
Originally Posted by ranlevinstein View Post
7.How did you create 2 dimensional trajectories for your robot during auto?
We cheated. We had a rotational trapezoidal motion profile and a linear trapezoidal motion profile. We just started them at different times/positions, added them to each other, and let them overlay on top of each-other. It was a pain to tune, but worked well enough. We are going to try to implement http://arl.cs.utah.edu/pubs/ACC2014.pdf this summer.

Quote:
Originally Posted by ranlevinstein View Post
8.How do you sync multiple trajectories in the auto period? for example how did you make the arm of your robot go up after crossing a defense?

Thank you very much!
Our auto code was a lot of "kick off A, wait until condition, kick off B, wait until condition, kick off C, ..." So, we'd start a motion profile in the drive, wait until we had moved X far, and then start the motion profile for the arm. The controllers would calculate the profiles as they went, so all Auto actually did was coordinate when to ask what subsystem to go where. With enough motion profiles, and when you make sure they aren't saturated, you end up with a pretty deterministic result.

Awesome questions, keep them coming! I love this stuff.
Reply With Quote