![]() |
Drivetrain PID tuning
Today, I was encouraging my rookie programmers to utilize the NavX to experiment with PID Control in order to make our robot drive straight. Given that we've never done this in a season, one of the things that crossed my mind is how we should deal with the differences in CoFs between our lab's carpet and that of a true to life field. What have other teams done to account for this? Have you guys just purchased carpet, and just calibrated it on that? What would you use to re-tune your loop at competition?
Thanks so much! |
Re: Drivetrain PID tuning
Sensitivity to carpet variation is somewhat dependent on your drivetrain geometry and dynamics. A 6 wheel drive, dropped-center robot with a roughly central CoM and hard wheels is going to turn pretty similarly on a wide variety of floor surfaces. Meanwhile, a 4 wheel drive robot with a long wheelbase and pneumatic wheels may scrub quite differently depending on carpet.
Ideally your PID algorithm can be tuned to compensate for various types of floor conditions (after all, well-worn vs. brand new field carpet can be quite different in its own right!). If you are able to control your robot on a couple different types of surfaces at home (including whatever you have that is most similar to the field surface), you ought to be good when you get to competition. |
Re: Drivetrain PID tuning
We're able to get pretty good straight driving using only the P term with the navX, so that may be worth trying. As for carpet, a local store gave us a 5x12 foot square of the official carpet (different color though).
|
Re: Drivetrain PID tuning
Quote:
As far as color, if you insist on the right color, you'd need a new piece (or two) of carpet each year. |
Re: Drivetrain PID tuning
Things to watch out for when doing this, based on personal experience:
1) It is very hard for a loop to keep you driving straight at max speed, because if your motors are saturated you can only slow down one side to adjust, rather than both slow down one side and speed up the other. If you give yourself some headroom, it will work much better. 2) Unless you are using cascading control (i.e. feeding the output of your heading loop to a wheel velocity loop), it is likely that you won't be able to make the p gain high enough on the heading loop to make steady state error acceptably small without introducing instability. A quick and dirty fix for this is to simply add or subtract some minimum output to/from the calculated heading loop output whenever it is outside of some tolerance around 0. |
Re: Drivetrain PID tuning
Quote:
1.We do a quick system id on the yaw axis a. Apply a moderate amplitude yaw step (usually 1/2 max input on whatever yaw command input you have) b. Model the angular rate output with the equation rate = input*k*(1 - exp(-t/tau)) 2. design a controller using the following architecture; error = (yaw_cmd - yaw_rate) motor_cmd = PID(error, Kp, Ki, Kd) where: Kp = gain/K*tau Ki = gain/K Kd = 0 gain = 5 to 10 (arbitrary, desired bandwith in rad/sec); 3. Vary gain to get the command response you want. We start at 10, and if it's too sluggish bump it up, if it oscillates or limit cycles (bounces back and forth due to backlash) we back it off. Sorry for the terse explanation, but that's pretty much it. We do all our own code, so the PI controller is just written into the yaw service function. Sorry I don't have the code right now, but I can find it. Cheers, Steve. |
Re: Drivetrain PID tuning
Can anyone explain to me why so many teams use gyros for driving straight instead of encoders?
|
Re: Drivetrain PID tuning
Quote:
*aka "math" |
Re: Drivetrain PID tuning
Quote:
Once the wheels have slipped against the carpet/floor/obstacle and you don't know how much, you can't reliably use the encoders (by themselves) to determine orientation. Gyros have more drift, but are not subject to this sudden loss of calibration. |
Re: Drivetrain PID tuning
Quote:
David |
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
Code:
Robot.drivetrain.arcadeDrive(DriveForwardSpeed, (Robot.drivetrain.getGyroAngle().getAngle()));Code:
Robot.drivetrain.arcadeDrive(-DriveForwardSpeed, (-(Robot.drivetrain.getGyroAngle().getAngle()) * Kp+.1)); |
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
For tele-op drive straight, a button on the xBox controller sets the current heading as the desired heading value then replaces the driver's rotation joystick value with the output of the heading proportional controller. Essentially the driver is only controlling thrust at that point and the loop maintains heading. For our use, a proportional only loop worked but you could set up PID and experiment with the tuning. David |
Re: Drivetrain PID tuning
In 2015 we used Mecanum wheels and one thing we really noticed was that the robot would rotate and drive forward well, but generated a lot more random slipping when moving sideways. We ended up using encoders for forward and lateral positioning and the gyro for heading. We could have used the encoders (one on each wheel) to determine heading, but the slip was giving us problems.
It was worse when the wheels got worn out. we were using the 6" Vexpro wheels, very cost effective but had a very noticeable life span for the rollers. Replacement wheels altered our autonomous timing required for the 3 tote auto. Cheers, Steve. |
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
A gyro can't help you measure translational motion, of course. If you use a multi-DOF IMU with gyros AND accelerometers, you can measure linear acceleration...but trying to obtain precise translational displacement from these is not going to work well (maybe this is what you were referring to). But you can combine a gyro with encoders to give you the "best of both worlds" and follow a profiled path while correcting for yaw errors. As long as the profile contains yaw information, you can use a PID controller (often a P controller is enough) to add a bit of velocity to one side and subtract it from the other to keep you on track. For more details, see: https://github.com/Team254/FRC-2016-...rive.java#L385 (our "drive straight" mode engaged by the driver by holding down a button) and: https://github.com/Team254/FRC-2016-...rive.java#L396 (our path following mode used for autonomous mode) |
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
Our system is to run an independent profile on each side of the robot, where each wheel follows the profile and corrects itself based on the error from the end point. This way, at the end of the loop, the setpoint for each side is the endpoint of the profile, so it ends up correcting itself to the right place. I guess what I'm saying is that when you use the gyro to go straight (based on yaw) you're adding a new variable (yaw) instead of interpreting yaw as a difference of distances. How do you ensure that that doesn't become a problem? Hope this makes some sense. |
Re: Drivetrain PID tuning
Quote:
For example: Say we want to go in a straight line for 10 feet. You would generate left and right profiles that in this case would be identical. You begin following each profile. At some point, maybe there's a bunch in the carpet on the left side, so your left controller begins lagging a bit because of the disturbance...but the right controller keeps tracking accurately. If this happens, your robot is now veering off to the left. The gyro's role in all of this being to coordinate the execution of your independent left and right profiles. If you are using a gyro to track your actual yaw angle compared to your profile, you'll see that you are now veering left, so your left side should try *extra* hard to get back on track, and the right side should ease up just a bit. With enough gain on the gyro term, the left side should recover very quickly and get synchronized with the right side before you've drifted too far from your intended path. |
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
angle = (right_distance - left_distance) / width distance = (left_distance + right_distance) / 2 You can do a similar transform for your powers (pardon any sign errors) to get back to actual outputs you physically have. left_voltage = distance_voltage - turn_voltage right_voltage = distance_voltage + turn_voltage This then lets you control what you care about. In the presence of tire slip and tire wear, you won't always go straight with just encoders. A gyro has a different set of issues (noise), but isn't affected by those problems. So, we use the gyro for the angle of the robot instead of computing the angle as above. Just re-phrasing your loops to be an angle, distance pair of loops has huge benefit. Unless your robot has all it's mass perfectly centered over the two drive wheels, your left, right PID loop won't be able to do good distance control and turn control without compromises. I tend to find that good distance control results in a small amount of turn chatter and oscillation. (You can work out the physics to show that the two sides are coupled in left, right, but not in angle, distance) A angle, distance loop doesn't make that assumption. If you really want to do left, right with a gyro, you can reverse the equations above. |
Re: Drivetrain PID tuning
Quote:
The Motion Profiling you're describing, like most motion profiling, is based upon distance, velocity and acceleration. Something to note is that these all function in a single dimension. For devices like actuation arms or conveyors, this makes sense, as there is only one direction of motion. (there can still be issues here in tracking, but that is not related to a difference in distances) If you want to start using this in a 2D sense (i.e. a drive base), these distances can be misread. For example, if a wheel (or track) on one side of your drive base slips (assuming 'tank' drive), it will mistakenly read a distance, even though it hadn't moved that far. To the code, your drive base is tracking properly, but in the real world it isn't. This is a common problem with drive bases. The most common way to fix this is to add an extra proportional gain based on the error between what you want your heading to be, and what your heading is reported to be by the gyroscope (per Austin's example). Let's say you have the following code: Code:
float left_power = calc_power_left(time, profile_l, encoder_l);Code:
float gyro_heading = ... your gyro code ...The main point I'm trying to clear up here is that it isn't entirely possible to use encoders for correction, as they rely on continuous, perfect connection to the field floor. Adding in a gyroscope will account for any errors in heading that the encoders, wheels or field introduce. I hope this clears up any misconceptions you have. |
Re: Drivetrain PID tuning
Quote:
1. Assuming that you use your gyro to calculate your angular offset rather than "angle = (right_distance - left_distance) / width." How would you calculate the turn voltage part of the bottom equation? Quote:
2. Do you have any tips for tuning PID loops in cases with lots of friction like turning PID loops? Jared (very kindly!) sent me some tips on tuning PID loops before, but I'm curious to see if there are other viewpoints on this in situations with lots of friction. |
Re: Drivetrain PID tuning
Quote:
Quote:
If you've got a bunch of friction, you end up needing to slow things down a bit. Friction is a pain to deal with. You also need to ask yourself really how accurate you need to be. If you can tolerate moderate steady state error, leave it as a PD loop. As the robot goes faster, it takes less energy to get it to steer, which works in your favor. If you really need good tracking, you are going to have to work at tuning I correctly. Consider running in low gear if you have a transmission so friction is a smaller portion of your overall torque. The most annoying steering loop I tuned was 254's 2011 robot, geared for crazy speeds. We needed to run auto in high gear too, which meant we were close to saturation all the time. The most annoying issue I've had tuning heading PID loops was where there was lag in the gyro angle reading. That phase lag meant I couldn't push the bandwidth of the loop up to anything useful. I had to fix that before I could get it to stabilize well. I debugged that by plotting the gyro and encoder headings. Run your loops at 100 - 200 hz. You want to run your loops at 10x the frequency of the highest frequency you want to control. So, if you want to control at 10 hz, you need a 100 hz loop. The more reliable you can get your loop timing, the better. We go to great lengths to hit a 5 ms +- 5% loop timing, and it helps a lot. The most important part here is to plot everything. Plot your error vs time, and watch it evolve. Plot the power due to P, I, D, FF. Plot the encoder based heading and the gyro based heading. It's possible but hard to tune these things by eye. Honestly, sometimes I think it's easier to rough tune them by listening to them and listening for the overshoot, and then reaching for the plots when I'm stuck. I also like to grab it and feel the loop, though you have to be very careful since robots can cause lots of damage fast. We use more complicated controllers, which means I have less recent relevant robot experience than I'd like here. I should probably go grab a robot and tune a PID heading loop again just to have some more guidance. |
Re: Drivetrain PID tuning
Quote:
|
Re: Drivetrain PID tuning
Quote:
We've gone almost exclusively to a PI controller for yaw rate for stabilization, since in teleop we're generally commanding yaw rate anyway. In autonomous we just program rate*time for heading changes, the integrator in the controller almost always gets us close enough. We've done heading control with feed forward for more bandwidth, but it was overkill for the particular application we tried it with. One of the first things we do in our gyro service function is to calculate (if necessary) and provide robot heading, and heading rate so that we don't need to derive it in a controller. BTW, we generally run at 50 Hz, and target around 10 rad/sec for rate bandwith (a little less that 2 Hz). Our recent setups have been giving us around 30 millicesonds of delay between command and robot response, and 10 rad/s is about the point where we have to start to get more creative with a controller. We may try 100 Hz this year, depending on what we need to do. Cheers, Steve. |
Re: Drivetrain PID tuning
Quote:
float delta_angle = MATH.IEEEremainder(desired_heading - gyro_heading,360); // This is our error in alignment https://www.chiefdelphi.com/forums/s...3&postcount=36 https://msdn.microsoft.com/en-us/lib...vs.110%29.aspx http://en.cppreference.com/w/cpp/numeric/math/remainder |
Re: Drivetrain PID tuning
Quote:
This is almost a whole new thread, but it's actually hard to write code that is hard real-time on the roboRIO. Hard real-time means that 100% of the time, your code will finish in X us. That means all your algorithms need to run in constant bounded time, and they can't use any system calls which don't run in constant bounded time either. This means you need to avoid - Allocating memory (new, malloc, etc). - file IO. (It can take an unbounded amount of time for your write system call to complete). - algorithms which don't take constant execution time. - Any other operations which aren't constant time. https://rt.wiki.kernel.org/index.php/RT_PREEMPT_HOWTO has some good info on what real-time means. If you are interested in debugging real-time issues, I'm happy to post some more detailed information. I should really do a CD post some time on one of the ones I've found. For us for logging, this means that we don't log data from our controls thread. We queue it up with a real-time bounded length queue, and write it to a USB stick mounted on the roboRIO from another process. This is a pain, but well worth it. Another hack I'll use for debugging is to monitor the execution time of the syscalls I care about, (for example, the control loop execution time including logging), and re-run the test if there was a timing violation. This won't be real-time for running during a match where you can't replay if there was a timing violation, but lets you debug something quickly and know when you've affected your test results. |
Re: Drivetrain PID tuning
Quote:
Quote:
Quote:
|
| All times are GMT -5. The time now is 11:09. |
Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi