Go to Post And then I learned how to use the lathe...long story short, I ditched my plans to become a music major and became an engineering student. - Karibou [more]
Home
Go Back   Chief Delphi > Technical > Programming > C/C++
CD-Media   CD-Spy  
portal register members calendar search Today's Posts Mark Forums Read FAQ rules

 
 
 
Thread Tools Rate Thread Display Modes
Prev Previous Post   Next Post Next
  #3   Spotlight this post!  
Unread 24-01-2012, 11:21
Jared Russell's Avatar
Jared Russell Jared Russell is offline
Taking a year (mostly) off
FRC #0254 (The Cheesy Poofs), FRC #0341 (Miss Daisy)
Team Role: Engineer
 
Join Date: Nov 2002
Rookie Year: 2001
Location: San Francisco, CA
Posts: 3,077
Jared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond reputeJared Russell has a reputation beyond repute
Re: PIDController, Counter Class, Speed Controls

There is one common pitfall associated with switching from distance to rate/speed as the process variable.

Consider a position control loop as implemented by WPIlib:

Code:
Motor Voltage = Kp*error + Ki*error_sum + Kd*(error-error_last)
Error is in units of distance; the output is in units of percentage of motor voltage (roughly, speed). When you have zero error (and zero error_sum and zero error_last...e.g. you are exactly at your goal) in a position control loop, you command a zero motor speed. This make sense; stopping will leave you at your goal.

Now consider what would happen if you implemented the same loop, but switch the "error" units from distance to speed. When you have zero error in a velocity control loop, you do NOT want to command a zero motor speed. That would slow the motor and result in MORE error. Your best bet is probably to command the motor to keep going whatever speed it was at last!

There are two ways you can get your velocity controller behaving in this situation:

(1) You need to treat P and I as if they were actually D and P, respectively! This makes sense; you are basically taking the time-derivative of position, which is speed, but are still commanding the same quantity (voltage). Hence the meaning of your gains changes to reflect the derivative of the input.

(2) You can make a slight tweak to the way the PID output is used. Instead of

Code:
Output = ...
you can simply accumulate the output:

Code:
Output = Output + ...
Using the second method, you can think of your output not being "Voltage", per se, but rather "Change in Voltage". In other words, you are taking the derivative of the left side of the equation as well as the right.
Reply With Quote
 


Thread Tools
Display Modes Rate This Thread
Rate This Thread:

Posting Rules
You may not post new threads
You may not post replies
You may not post attachments
You may not edit your posts

vB code is On
Smilies are On
[IMG] code is On
HTML code is Off
Forum Jump


All times are GMT -5. The time now is 08:53.

The Chief Delphi Forums are sponsored by Innovation First International, Inc.


Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi