|
|
|
![]() |
|
|||||||
|
||||||||
![]() |
| Thread Tools | Rate Thread | Display Modes |
|
#1
|
|||
|
|||
|
Encoder as PIDSource
WPILib question.
Is there a reason that the Encoder class doesn't implement the PIDSource interface? I see that it includes the header file but it doesn't actually inherit from PIDSource. Is this just a "TODO" for the lib or is there something fundamental that prevents using an encoder as PIDSource? I'm asking because I was thinking we might want to use a PIDController to control the position of a "elevator" on our robot. Example, I might have a victor (the PIDOutput) that controls a motor for a chain drive that moves the elevator up and down and an encoder that tells me when i have reached my desired position. |
|
#2
|
||||||
|
||||||
|
Re: Encoder as PIDSource
Maybe the reason it wasn't implemented is because one person what might want to use position as the PIDSource and another would want to use the rate as the PIDSource.
|
|
#3
|
|||
|
|||
|
Re: Encoder as PIDSource
ya that's a good point. Any suggestions on how to control the position of my elevator? I think I want some kind of feedback control. I'd rather not just run the motor at a specific speed for a specific time.
|
|
#4
|
||||
|
||||
|
Re: Encoder as PIDSource
We just ran into this problem a couple hours ago. Does anyone know how to use the encoder as a PID source?
|
|
#5
|
|||
|
|||
|
Re: Encoder as PIDSource
For position control, the GetRaw() and/or GetDistance() methods will probably provide the data you need. As far as how to do it, a simple subclass of both Encoder and PIDSource that implements the PidGet method should do the trick.
|
|
#6
|
|||
|
|||
|
Re: Encoder as PIDSource
Thanks for the help everyone. I put together the subclass that Alexander described and will post it here in case it helps anyone else. It does compile but hasn't been tested in any way.
PIDEncoder.h Code:
#include "Encoder.h"
#include "PIDSource.h"
class PIDEncoder : public Encoder, PIDSource
{
public:
//constructor
PIDEncoder(UINT32 aSlot, UINT32 aChannel,
UINT32 bSlot, UINT32 bChannel,
bool reverseDirection, EncodingType encodingType);
//destructor
~PIDEncoder();
//virtual from PIDSource
double PIDGet();
private:
};
PIDEncoder.cpp Code:
#include "PIDEncoder.h"
//constructor
PIDEncoder::PIDEncoder(UINT32 aSlot, UINT32 aChannel,
UINT32 bSlot, UINT32 bChannel,
bool reverseDirection, EncodingType encodingType) : Encoder(aSlot,aChannel,bSlot,bChannel,reverseDirection,encodingType)
{
}
//destructor
PIDEncoder::~PIDEncoder()
{
}
//virtual from PIDSource
double PIDEncoder::PIDGet()
{
return this->GetDistance();
}
|
|
#7
|
||||
|
||||
|
Re: Encoder as PIDSource
Quote:
I have tried for 2 years to use the PIDSource class to drive our robot a certain distance with the encoders and failed each time. I always run out of time, and I, still after 2 years of beating through the C++ code, do not understand classes completely. I muddle through. This year me and the students HAVE to figure this out in order for the robot they designed to work correctly, so needless to say, I am very interested in this thread. How do you use your above PIDEncoder in the robot main code to get the elevator to stop at the correct distance? I see the class and that looks nice but I don't know how to use it. If you want to PM me to keep "spoilers" away that's fine, though honestly I guarantee you there are many students and mentors out there running into the same problems. |
|
#8
|
|||
|
|||
|
Re: Encoder as PIDSource
cplusplus.com has a good guide if you want to solidify your knowledge of C++.
To use the class that jwakeman posted, you need to make use of PIDController. Basically, initialize a PIDController with P, I, and D values, a PIDSource, and a PIDOutput in your constructor. So, say you use a victor to drive your elevator and an encoder to measure distance, you might have something like this: Code:
Victor *ap_elevatorDrive;
PIDEncoder *ap_elevatorEncoder;
PIDController *ap_elevatorControl;
Constructor()
{
ap_elevatorDrive = new Victor(args);
ap_elevatorEncoder = new PIDEncoder(args);
ap_elevatorControl = new PIDController(1.0, 0.0, 0.0, ap_elevatorEncoder, ap_elevatorDrive);
}
The WPILib User's Guide has a complete example of position control with a PIDController and a potentiometer. Hope that helped, -Alexander |
|
#9
|
||||
|
||||
|
Re: Encoder as PIDSource
Quote:
Our goal this week is to get some sort of prototype setup so we can work on encoders since they have become mandatory for us this year with the design we want. Thanks everyone. (P.S. I will read that tutorial you hyperlinked since I still have a hard time figuring out when to use *, &, ::, ., -> and all the other heiroglyphics in C++. If there was one simple use throughout for calling classes and such I could get it. The Getting Started with C++ guide from the FIRST website made an attempt to explain these differences in pointers and references and I am getting closer, but it could do with some full sample code examples instead of just snippets) |
|
#10
|
|||
|
|||
|
Re: Encoder as PIDSource
The example Alexander gave is probably a little simpler but here is a class we are working on to represent the elevator controller. Basically this class inherits from PIDController (it "is" a PIDController) and contains the victor and encoder objects that are required for PIDOputput and PIDSource. It is still under construction but it compiles and illustrates the concept I think. Also, our team is hosting an open source project for our development efforts on google code (http://code.google.com/p/first-team63/). Can't guarantee when/what will get posted here but I will try to keep it updated as we make progress. Here the elevator class as it stands now:
ElevatorController.h: Code:
#include "PIDController.h"
#include "Victor.h"
#include "PIDEncoder.h"
class ElevatorController : public PIDController
{
public:
ElevatorController(float p, float i, float d,float period = 0.05);
~ElevatorController();
void SetHeight(double dHeight);
private:
Victor *motorController;
PIDEncoder *encoder;
};
ElevatorController.cpp: Code:
#include "ElevatorController.h"
ElevatorController::ElevatorController(float p, float i, float d, float period)
: PIDController(p,i,d,this->encoder, this->motorController, period)
{
this->encoder = new PIDEncoder(1, 1, 1, 1, false, CounterBase::k1X); //pass proper parameters here later
this->motorController = new Victor(1,1); //and here
this->PIDController::SetInputRange(0.0,0.0);//and here
}
ElevatorController::~ElevatorController()
{
}
void ElevatorController::SetHeight(double dHeight)
{
this->PIDController::Reset();
this->PIDController::SetSetpoint(dHeight);
this->PIDController::Enable();
}
|
|
#11
|
|||
|
|||
|
Re: Encoder as PIDSource
Quote:
There is a new SetPIDSourceParameter() method that lets you pick which one is your process variable. -Joe |
|
#12
|
||||
|
||||
|
I just tried to implement what you guys have been giving me into my code and when I try to compile I get the following error:
C:/WindRiver/Team2992_2011_Code_1/IterativeDemo.cpp:150: error: `PIDSource' is an inaccessible base of `PIDEncoder' and it highlights in red the line from my code below "elevatorControl = new PIDController(0.1, 0.01, 0.001, elevatorEncoder, elevatorMotor);" I did tweak jwakeman's PIDEncoder.h and ".cpp to below because I prefer to do without the slot designation for the cRio. PIDEncoder.h Code:
#include "Encoder.h"
#include "PIDSource.h"
class PIDEncoder : public Encoder, PIDSource
{
public:
//constructor
PIDEncoder(UINT32 aChannel,UINT32 bChannel,
bool reverseDirection, EncodingType encodingType);
PIDEncoder(UINT32 aSlot, UINT32 aChannel,
UINT32 bSlot, UINT32 bChannel,
bool reverseDirection, EncodingType encodingType);
//destructor
~PIDEncoder();
//virtual from PIDSource
double PIDGet();
private:
};
Code:
#include "PIDEncoder.h"
//constructor
PIDEncoder::PIDEncoder(UINT32 aChannel, UINT32 bChannel,
bool reverseDirection, EncodingType encodingType) :
Encoder(aChannel,bChannel,reverseDirection,encodingType)
{
}
PIDEncoder::PIDEncoder(UINT32 aSlot, UINT32 aChannel,
UINT32 bSlot, UINT32 bChannel,
bool reverseDirection, EncodingType encodingType) : Encoder(aSlot,aChannel,bSlot,bChannel,reverseDirection,encodingType)
{
}
//destructor
PIDEncoder::~PIDEncoder()
{
}
//virtual from PIDSource
double PIDEncoder::PIDGet()
{
return this->GetDistance();
}
Under Iterative Robot Class: Code:
PIDEncoder *elevatorEncoder; PIDController *elevatorControl; Victor *elevatorMotor; Code:
elevatorEncoder = new PIDEncoder(11,12,true,Encoder::k4X); elevatorEncoder->SetDistancePerPulse(0.04318); //inches //UPDATE!! elevatorEncoder->Start(); elevatorMotor = new Victor(5); elevatorControl = new PIDController(0.1, 0.01, 0.001, elevatorEncoder, elevatorMotor); |
|
#13
|
|||
|
|||
|
Re: Encoder as PIDSource
Instead of
Code:
class PIDEncoder : public Encoder, PIDSource Code:
class PIDEncoder : public Encoder, public PIDSource |
|
#14
|
||||
|
||||
|
Re: Encoder as PIDSource
Dang it! We had used the information that you guys had given us and finally had our robot working and PIDing with the encoders and then the WPI Library got updated with a mandatory update and broke it all again! I get a wall of red from redundant PIDSources or some such thing.
Grr, can someone please help me get set back up, now using the default, updated PIDController class that has the encoders as a source now. Specifically can someone help me figure out how to tell the encoder to use distance as its source? So instead of constructing my encoders with the nice subclasses from earlier in the thread, I do: Code:
Encoder *elevatorEncoder; PIDController *elevatorControl; //constructor elevatorEncoder = new Encoder(11,12,true,Encoder::k4X); elevatorEncoder->SetDistancePerPulse(0.009); //inches //UPDATE!! elevatorEncoder->Start(); elevatorControl = new PIDController(0.1, 0.01, 0.001, elevatorEncoder, elevatorMotor); //periodic elevatorControl->Enable(); elevatorControl->SetPID(((leftStick->GetThrottle()+1)/2)*0.1, ((rightStick->GetThrottle()+1)/2)*0.01,0.0); //tuning elevatorControl->SetSetpoint(ElevatorPosition); "void Encoder::SetPIDSourceParameter ( PIDSourceParameter pidSource )" from the help file, but I can't find the list of variables which denotes distance. Can someone help me figure out how to get setup correctly? |
|
#15
|
|||
|
|||
|
Re: Encoder as PIDSource
Just add the call to SetPIDSourceParameter in your constructor. The PIDSourceParameter enum is defined in the Encoder header file and in the doxygen help.
-Joe |
![]() |
| Thread Tools | |
| Display Modes | Rate This Thread |
|
|