![]() |
Re: WPILib PID controller object
Quote:
|
Re: WPILib PID controller object
Quote:
If you still don't understand exactly how the PIDController class works, here's a rundown of the methods that get called when it runs:
|
Re: WPILib PID controller object
Quote:
Once I just sent the information in terms of the 10 bit "raw" data the potentiometer outputs my robot started to converge. I am still trying to figure out what values of P,I, & D to send so that the turret doesn't jitter, but I understand that is mostly empirical depending on your system. Edited to Ask: How did you look at the source code of the WPILib to find what the PIDGet() call was doing? I can only find the .h files for the different classes. Needless to say it would be easier to figure out my problems if I could see what each of the library classes was actually supposed to be doing. |
Re: WPILib PID controller object
|
Re: WPILib PID controller object
Quote:
|
Re: WPILib PID controller object
Quote:
I love this forum, you guys are great with your fast responses to those of us muddling through this stuff for the first time. |
Re: WPILib PID controller object
Quote:
I am using the variable name horizontalDestination = par1.centered_mass_x_normalized which gives me a nice -1 to 1 for the position of the target on the camera from centered. How do I make horizontalDestination a PIDSource so that the PIDController will drive the turret motor until horizontalDestination = 0? |
Re: WPILib PID controller object
We've just coded this last night and hope to try it tonight. You need to derive your own class from the PIDSource class. In PIDSource.h, notice that there is one method defined:
virtual double PIDGet() = 0; This is what's known as a pure virtual method; There is no default implementation This means you can't create a PIDSource object, only one derived from it with this method overridden with your own. The code looks something like this: // .h file #include <WPILib.h> class MyPIDSource : public PIDSource { public: double PIDGet(); } // .cpp file #include "MyPIDSource.h" double MyPIDSource::PIDGet() { double pidSourceValue; // calculate 'double' value that you want compared to the set point // feel free to format it the same as you expect with your set point pidSourceValue = ... // return value return pidSourceValue; } Before you create your controller object, you must create an instance of your class. Pass this pointer as a parameter to PIDController for the PIDSource arg. Now, every 50 ms (assuming you've started it going), the PIDController will read the PID source, compare the value to the set point, do it's PID calculations, and write the new value to the PID output device. With our setup, we are turning a turret that has a camera mounted on it to track the vision target. My PID Source uses the X component of the Particle report to get the error value. So our set point is permanently set to 0 (centered in the camera). But we have to take into account the position of the turret with respect to our two end stops. As we get closer to one of our stops (as read from our 10 turn pot attached to the turret gears) we have to supply a smaller number until it gets to 0 at the end, assuming we're driving it in that direction. We can also disable our 'auto tracking' by just returning a 0, and allow manual control by just passing back the z component of a joystick to represent the value. It's actually quite powerful. I'll let you know how it works. Hope this helped... Steve |
Re: WPILib PID controller object
Quote:
---------------------------------------- I have a CamSource.h which is: ---------------------------------------- #include "WPILib.h" class CamSource : public PIDSource { public: CamSource(); double PIDGet(); void SetSource(double); private: double source; }; ------------------------------------------------ My CamSource.cpp file is: ---------------------------------------- #include "CamSource.h" CamSource :: CamSource() {} void CamSource :: SetSource (double sourcedum) { source = sourcedum; } double CamSource :: PIDGet() { return source; } ---------------------------------------- Then in my main code I do the following to use it. Basically I set the CamSource to what the X difference on the camera is, and then feed it to my PIDController. RobotCode.h: ---------------------------------------- PIDController *turretCamControl; CamSource *CameraBrains; RobotCode.cpp ---------------------------------------- CameraBrains = new CamSource(); turretCamControl = new PIDController(CamP, CamI, CamD, CameraBrains, TurretPIDMotor); Then in my teleoperated periodic: turretCamControl->Enable(); CameraBrains->SetSource(horizontalDestination); turretCamControl->SetSetpoint(0); ----------------------------------------- I think it will work, at least it compiles fine. horizontalDestination is the normalized X parameter from the camera. Thanks for your help, what you have outlined is pretty much the route I went as well. I don't know why, WPI couldn't just write a controller that allows us to just input a dang variable. It would be much easier. |
Re: WPILib PID controller object
All that code I posted above seemed to work fine. I haven't got the camera on the actual robot yet, that'll be tonight or tomorrow but the motor I had it on separately seemed to track correctly with the camera as the PIDSource.
Thanks again for the help. |
Re: WPILib PID controller object
Glad to hear you have some initial success. What I noticed (and you may have accounted for this in your real code) is that it does not take into account any stops you may have. Can the turret turn 360 deg? We have two stops and a pot tied to the gears to give us an absolute position. We have to use that info to slow down/stop near the ends.
Steve C. |
Re: WPILib PID controller object
Quote:
I troubleshot this for a few hours before removing the various Set Jaguar statements throughout my code. Now I have a variable that I modify throughout the code, and only sent the actual Set statement once. I was used to nothing actually being commanded till the end of each loop and so I was used to being able to modify stuff after I had set it once earlier, but it looks like I can't get away with this now. I have no idea how this is gonna work with myPIDControllers yet but it doesn't bode well. Right now I am trying to figure out how I am gonna make sure the turret doesn't "jitter" when it gets to the limit switches. I am still using blanket if-thens at the end of my teleop loop for the turret until I can figure out some way to control my PID loop. |
Re: WPILib PID controller object
We have our PIDController now up and running with either the z axis of a joystick or the x offset of a camera (same ranges) to give it its input (PIDSource). Last night, we had the turret tracking the ball pretty well. Time to tweak the PID constants:eek:
If you don't have a turret position sensor device of some sort, you can still incorporate the limit switches into the PID controller setup. In your PIDSource object, check the limit switch for the direction you are turning toward. If closed, return a 0.0 to stop the motor. If you're still getting some 'jitter', you can set a flag for the direction you were travelling to keep the output 0 until you start trying to track toward the other direction. The problem with just limit switches is that you can't start slowing down before the end stops. One more thing that just struck me... If you're trying to use Set statements for the same Jaguar that the PIDController is using, you will be fighting it. The PID loop runs every 50ms. You can set it to 0, but the PIDController will shortly overwrite it. Steve C. |
Re: WPILib PID controller object
Quote:
As once in a blue moon your camera "spaz" while it is tracking? Very rarely, but often enough to make it a pain, our camera tracker will move out of position quickly then recover for no apparent reason. I think it's because of a classic concurrency issue where source is being read and written at the same time. The PID controller runs in a separate task, and so potentially both SetSource and PIDGet could be called at the same time. Would any more experienced programmers out there recommend locks? And if so, how would you implement them in the quoted code? |
Re: WPILib PID controller object
Quote:
I put a speed cap on the turret and it now works good enough for our purposes. I had the same problem with the PID controller stuff on my turret when it was trying to goto a position stated by another potentiometer. I don't know if I just don't understand the language good enough to debug it, but this year's experience has tailored my expectations from now on. I'll probably still try to get PID stuff working on future robots (as I have for the last 3 years), but I'll always have a backup plan to fall back on like I did this year. Our turret is now driven by joystick and the camera routine works adequately enough to zero in on a target once the user gets it close. |
| All times are GMT -5. The time now is 12:18. |
Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi