blob: c8fb63f31921e41be2690195d1e592514ac8ace0 [file] [log] [blame]
Brian Silverman26e4e522015-12-17 01:56:40 -05001/*----------------------------------------------------------------------------*/
Brian Silverman1a675112016-02-20 20:42:49 -05002/* Copyright (c) FIRST 2008-2016. All Rights Reserved. */
Brian Silverman26e4e522015-12-17 01:56:40 -05003/* Open Source Software - may be modified and shared by FRC teams. The code */
Brian Silverman1a675112016-02-20 20:42:49 -05004/* must be accompanied by the FIRST BSD license file in the root directory of */
5/* the project. */
Brian Silverman26e4e522015-12-17 01:56:40 -05006/*----------------------------------------------------------------------------*/
7
8#include "PIDController.h"
9#include "Notifier.h"
10#include "PIDSource.h"
11#include "PIDOutput.h"
12#include <math.h>
13#include <vector>
14#include "HAL/HAL.hpp"
15
16static const std::string kP = "p";
17static const std::string kI = "i";
18static const std::string kD = "d";
19static const std::string kF = "f";
20static const std::string kSetpoint = "setpoint";
21static const std::string kEnabled = "enabled";
22
23/**
24 * Allocate a PID object with the given constants for P, I, D
25 * @param Kp the proportional coefficient
26 * @param Ki the integral coefficient
27 * @param Kd the derivative coefficient
28 * @param source The PIDSource object that is used to get values
29 * @param output The PIDOutput object that is set to the output value
30 * @param period the loop time for doing calculations. This particularly effects
31 * calculations of the
32 * integral and differental terms. The default is 50ms.
33 */
34PIDController::PIDController(float Kp, float Ki, float Kd, PIDSource *source,
35 PIDOutput *output, float period) {
36 Initialize(Kp, Ki, Kd, 0.0f, source, output, period);
37}
38
39/**
40 * Allocate a PID object with the given constants for P, I, D
41 * @param Kp the proportional coefficient
42 * @param Ki the integral coefficient
43 * @param Kd the derivative coefficient
44 * @param source The PIDSource object that is used to get values
45 * @param output The PIDOutput object that is set to the output value
46 * @param period the loop time for doing calculations. This particularly effects
47 * calculations of the
48 * integral and differental terms. The default is 50ms.
49 */
50PIDController::PIDController(float Kp, float Ki, float Kd, float Kf,
51 PIDSource *source, PIDOutput *output, float period) {
52 Initialize(Kp, Ki, Kd, Kf, source, output, period);
53}
54
55void PIDController::Initialize(float Kp, float Ki, float Kd, float Kf,
56 PIDSource *source, PIDOutput *output,
57 float period) {
Brian Silverman1a675112016-02-20 20:42:49 -050058 m_controlLoop = std::make_unique<Notifier>(&PIDController::Calculate, this);
Brian Silverman26e4e522015-12-17 01:56:40 -050059
60 m_P = Kp;
61 m_I = Ki;
62 m_D = Kd;
63 m_F = Kf;
64
65 m_pidInput = source;
66 m_pidOutput = output;
67 m_period = period;
68
69 m_controlLoop->StartPeriodic(m_period);
Brian Silverman1a675112016-02-20 20:42:49 -050070 m_setpointTimer.Start();
Brian Silverman26e4e522015-12-17 01:56:40 -050071
72 static int32_t instances = 0;
73 instances++;
74 HALReport(HALUsageReporting::kResourceType_PIDController, instances);
75}
76
77PIDController::~PIDController() {
78 if (m_table != nullptr) m_table->RemoveTableListener(this);
79}
80
81/**
Brian Silverman26e4e522015-12-17 01:56:40 -050082 * Read the input, calculate the output accordingly, and write to the output.
Brian Silverman1a675112016-02-20 20:42:49 -050083 * This should only be called by the Notifier.
Brian Silverman26e4e522015-12-17 01:56:40 -050084 */
85void PIDController::Calculate() {
86 bool enabled;
87 PIDSource *pidInput;
88 PIDOutput *pidOutput;
89
90 {
Brian Silverman1a675112016-02-20 20:42:49 -050091 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -050092 pidInput = m_pidInput;
93 pidOutput = m_pidOutput;
94 enabled = m_enabled;
95 }
96
97 if (pidInput == nullptr) return;
98 if (pidOutput == nullptr) return;
99
100 if (enabled) {
Brian Silverman1a675112016-02-20 20:42:49 -0500101 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500102 float input = pidInput->PIDGet();
103 float result;
104 PIDOutput *pidOutput;
105
106 m_error = m_setpoint - input;
107 if (m_continuous) {
108 if (fabs(m_error) > (m_maximumInput - m_minimumInput) / 2) {
109 if (m_error > 0) {
110 m_error = m_error - m_maximumInput + m_minimumInput;
111 } else {
112 m_error = m_error + m_maximumInput - m_minimumInput;
113 }
114 }
115 }
116
117 if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
118 if (m_P != 0) {
119 double potentialPGain = (m_totalError + m_error) * m_P;
120 if (potentialPGain < m_maximumOutput) {
121 if (potentialPGain > m_minimumOutput)
122 m_totalError += m_error;
123 else
124 m_totalError = m_minimumOutput / m_P;
125 } else {
126 m_totalError = m_maximumOutput / m_P;
127 }
128 }
129
Brian Silverman1a675112016-02-20 20:42:49 -0500130 m_result = m_D * m_error + m_P * m_totalError + CalculateFeedForward();
Brian Silverman26e4e522015-12-17 01:56:40 -0500131 }
132 else {
133 if (m_I != 0) {
134 double potentialIGain = (m_totalError + m_error) * m_I;
135 if (potentialIGain < m_maximumOutput) {
136 if (potentialIGain > m_minimumOutput)
137 m_totalError += m_error;
138 else
139 m_totalError = m_minimumOutput / m_I;
140 } else {
141 m_totalError = m_maximumOutput / m_I;
142 }
143 }
144
145 m_result = m_P * m_error + m_I * m_totalError +
Brian Silverman1a675112016-02-20 20:42:49 -0500146 m_D * (m_error - m_prevError) + CalculateFeedForward();
Brian Silverman26e4e522015-12-17 01:56:40 -0500147 }
Brian Silverman1a675112016-02-20 20:42:49 -0500148 m_prevError = m_error;
Brian Silverman26e4e522015-12-17 01:56:40 -0500149
150 if (m_result > m_maximumOutput)
151 m_result = m_maximumOutput;
152 else if (m_result < m_minimumOutput)
153 m_result = m_minimumOutput;
154
155 pidOutput = m_pidOutput;
156 result = m_result;
157
158 pidOutput->PIDWrite(result);
159
160 // Update the buffer.
161 m_buf.push(m_error);
162 m_bufTotal += m_error;
163 // Remove old elements when buffer is full.
164 if (m_buf.size() > m_bufLength) {
165 m_bufTotal -= m_buf.front();
166 m_buf.pop();
167 }
168 }
169}
170
171/**
Brian Silverman1a675112016-02-20 20:42:49 -0500172 * Calculate the feed forward term
173 *
174 * Both of the provided feed forward calculations are velocity feed forwards.
175 * If a different feed forward calculation is desired, the user can override
176 * this function and provide his or her own. This function does no
177 * synchronization because the PIDController class only calls it in synchronized
178 * code, so be careful if calling it oneself.
179 *
180 * If a velocity PID controller is being used, the F term should be set to 1
181 * over the maximum setpoint for the output. If a position PID controller is
182 * being used, the F term should be set to 1 over the maximum speed for the
183 * output measured in setpoint units per this controller's update period (see
184 * the default period in this class's constructor).
185 */
186double PIDController::CalculateFeedForward() {
187 if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
188 return m_F * GetSetpoint();
189 }
190 else {
191 double temp = m_F * GetDeltaSetpoint();
192 m_prevSetpoint = m_setpoint;
193 m_setpointTimer.Reset();
194 return temp;
195 }
196}
197
198/**
Brian Silverman26e4e522015-12-17 01:56:40 -0500199 * Set the PID Controller gain parameters.
200 * Set the proportional, integral, and differential coefficients.
201 * @param p Proportional coefficient
202 * @param i Integral coefficient
203 * @param d Differential coefficient
204 */
205void PIDController::SetPID(double p, double i, double d) {
206 {
Brian Silverman1a675112016-02-20 20:42:49 -0500207 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500208 m_P = p;
209 m_I = i;
210 m_D = d;
211 }
212
213 if (m_table != nullptr) {
214 m_table->PutNumber("p", m_P);
215 m_table->PutNumber("i", m_I);
216 m_table->PutNumber("d", m_D);
217 }
218}
219
220/**
221 * Set the PID Controller gain parameters.
222 * Set the proportional, integral, and differential coefficients.
223 * @param p Proportional coefficient
224 * @param i Integral coefficient
225 * @param d Differential coefficient
226 * @param f Feed forward coefficient
227 */
228void PIDController::SetPID(double p, double i, double d, double f) {
229 {
Brian Silverman1a675112016-02-20 20:42:49 -0500230 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500231 m_P = p;
232 m_I = i;
233 m_D = d;
234 m_F = f;
235 }
236
237 if (m_table != nullptr) {
238 m_table->PutNumber("p", m_P);
239 m_table->PutNumber("i", m_I);
240 m_table->PutNumber("d", m_D);
241 m_table->PutNumber("f", m_F);
242 }
243}
244
245/**
246 * Get the Proportional coefficient
247 * @return proportional coefficient
248 */
249double PIDController::GetP() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500250 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500251 return m_P;
252}
253
254/**
255 * Get the Integral coefficient
256 * @return integral coefficient
257 */
258double PIDController::GetI() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500259 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500260 return m_I;
261}
262
263/**
264 * Get the Differential coefficient
265 * @return differential coefficient
266 */
267double PIDController::GetD() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500268 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500269 return m_D;
270}
271
272/**
273 * Get the Feed forward coefficient
274 * @return Feed forward coefficient
275 */
276double PIDController::GetF() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500277 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500278 return m_F;
279}
280
281/**
282 * Return the current PID result
283 * This is always centered on zero and constrained the the max and min outs
284 * @return the latest calculated output
285 */
286float PIDController::Get() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500287 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500288 return m_result;
289}
290
291/**
292 * Set the PID controller to consider the input to be continuous,
293 * Rather then using the max and min in as constraints, it considers them to
294 * be the same point and automatically calculates the shortest route to
295 * the setpoint.
296 * @param continuous Set to true turns on continuous, false turns off continuous
297 */
298void PIDController::SetContinuous(bool continuous) {
Brian Silverman1a675112016-02-20 20:42:49 -0500299 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500300 m_continuous = continuous;
301}
302
303/**
304 * Sets the maximum and minimum values expected from the input.
305 *
306 * @param minimumInput the minimum value expected from the input
307 * @param maximumInput the maximum value expected from the output
308 */
309void PIDController::SetInputRange(float minimumInput, float maximumInput) {
310 {
Brian Silverman1a675112016-02-20 20:42:49 -0500311 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500312 m_minimumInput = minimumInput;
313 m_maximumInput = maximumInput;
314 }
315
316 SetSetpoint(m_setpoint);
317}
318
319/**
320 * Sets the minimum and maximum values to write.
321 *
322 * @param minimumOutput the minimum value to write to the output
323 * @param maximumOutput the maximum value to write to the output
324 */
325void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) {
326 {
Brian Silverman1a675112016-02-20 20:42:49 -0500327 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500328 m_minimumOutput = minimumOutput;
329 m_maximumOutput = maximumOutput;
330 }
331}
332
333/**
334 * Set the setpoint for the PIDController
335 * Clears the queue for GetAvgError().
336 * @param setpoint the desired setpoint
337 */
338void PIDController::SetSetpoint(float setpoint) {
339 {
Brian Silverman1a675112016-02-20 20:42:49 -0500340 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
341
Brian Silverman26e4e522015-12-17 01:56:40 -0500342 if (m_maximumInput > m_minimumInput) {
343 if (setpoint > m_maximumInput)
344 m_setpoint = m_maximumInput;
345 else if (setpoint < m_minimumInput)
346 m_setpoint = m_minimumInput;
347 else
348 m_setpoint = setpoint;
349 } else {
350 m_setpoint = setpoint;
351 }
352
353 // Clear m_buf.
354 m_buf = std::queue<double>();
355 }
356
357 if (m_table != nullptr) {
358 m_table->PutNumber("setpoint", m_setpoint);
359 }
360}
361
362/**
363 * Returns the current setpoint of the PIDController
364 * @return the current setpoint
365 */
366double PIDController::GetSetpoint() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500367 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500368 return m_setpoint;
369}
370
371/**
Brian Silverman1a675112016-02-20 20:42:49 -0500372 * Returns the change in setpoint over time of the PIDController
373 * @return the change in setpoint over time
374 */
375double PIDController::GetDeltaSetpoint() const {
376 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
377 return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
378}
379
380/**
Brian Silverman26e4e522015-12-17 01:56:40 -0500381 * Returns the current difference of the input from the setpoint
382 * @return the current error
383 */
384float PIDController::GetError() const {
385 double pidInput;
386 {
Brian Silverman1a675112016-02-20 20:42:49 -0500387 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500388 pidInput = m_pidInput->PIDGet();
389 }
390 return GetSetpoint() - pidInput;
391}
392
393/**
394 * Sets what type of input the PID controller will use
395 */
396void PIDController::SetPIDSourceType(PIDSourceType pidSource) {
397 m_pidInput->SetPIDSourceType(pidSource);
398}
399/**
400 * Returns the type of input the PID controller is using
401 * @return the PID controller input type
402 */
403PIDSourceType PIDController::GetPIDSourceType() const {
404 return m_pidInput->GetPIDSourceType();
405}
406
407/**
408 * Returns the current average of the error over the past few iterations.
409 * You can specify the number of iterations to average with SetToleranceBuffer()
410 * (defaults to 1). This is the same value that is used for OnTarget().
411 * @return the average error
412 */
413float PIDController::GetAvgError() const {
414 float avgError = 0;
415 {
Brian Silverman1a675112016-02-20 20:42:49 -0500416 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500417 // Don't divide by zero.
418 if (m_buf.size()) avgError = m_bufTotal / m_buf.size();
419 }
420 return avgError;
421}
422
423/*
424 * Set the percentage error which is considered tolerable for use with
425 * OnTarget.
426 * @param percentage error which is tolerable
427 */
428void PIDController::SetTolerance(float percent) {
429 {
Brian Silverman1a675112016-02-20 20:42:49 -0500430 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500431 m_toleranceType = kPercentTolerance;
432 m_tolerance = percent;
433 }
434}
435
436/*
437 * Set the percentage error which is considered tolerable for use with
438 * OnTarget.
439 * @param percentage error which is tolerable
440 */
441void PIDController::SetPercentTolerance(float percent) {
442 {
Brian Silverman1a675112016-02-20 20:42:49 -0500443 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500444 m_toleranceType = kPercentTolerance;
445 m_tolerance = percent;
446 }
447}
448
449/*
450 * Set the absolute error which is considered tolerable for use with
451 * OnTarget.
452 * @param percentage error which is tolerable
453 */
454void PIDController::SetAbsoluteTolerance(float absTolerance) {
455 {
Brian Silverman1a675112016-02-20 20:42:49 -0500456 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500457 m_toleranceType = kAbsoluteTolerance;
458 m_tolerance = absTolerance;
459 }
460}
461
462/*
463 * Set the number of previous error samples to average for tolerancing. When
464 * determining whether a mechanism is on target, the user may want to use a
465 * rolling average of previous measurements instead of a precise position or
466 * velocity. This is useful for noisy sensors which return a few erroneous
467 * measurements when the mechanism is on target. However, the mechanism will
468 * not register as on target for at least the specified bufLength cycles.
469 * @param bufLength Number of previous cycles to average. Defaults to 1.
470 */
471void PIDController::SetToleranceBuffer(unsigned bufLength) {
Brian Silverman1a675112016-02-20 20:42:49 -0500472 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500473 m_bufLength = bufLength;
474
475 // Cut the buffer down to size if needed.
476 while (m_buf.size() > bufLength) {
477 m_bufTotal -= m_buf.front();
478 m_buf.pop();
479 }
480}
481
482/*
483 * Return true if the error is within the percentage of the total input range,
484 * determined by SetTolerance. This asssumes that the maximum and minimum input
485 * were set using SetInput.
486 * Currently this just reports on target as the actual value passes through the
487 * setpoint.
488 * Ideally it should be based on being within the tolerance for some period of
489 * time.
Brian Silverman1a675112016-02-20 20:42:49 -0500490 * This will return false until at least one input value has been computed.
Brian Silverman26e4e522015-12-17 01:56:40 -0500491 */
492bool PIDController::OnTarget() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500493 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
494 if (m_buf.size() == 0) return false;
Brian Silverman26e4e522015-12-17 01:56:40 -0500495 double error = GetAvgError();
Brian Silverman26e4e522015-12-17 01:56:40 -0500496 switch (m_toleranceType) {
497 case kPercentTolerance:
498 return fabs(error) < m_tolerance / 100 * (m_maximumInput - m_minimumInput);
499 break;
500 case kAbsoluteTolerance:
501 return fabs(error) < m_tolerance;
502 break;
503 case kNoTolerance:
504 // TODO: this case needs an error
505 return false;
506 }
507 return false;
508}
509
510/**
511 * Begin running the PIDController
512 */
513void PIDController::Enable() {
514 {
Brian Silverman1a675112016-02-20 20:42:49 -0500515 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500516 m_enabled = true;
517 }
518
519 if (m_table != nullptr) {
520 m_table->PutBoolean("enabled", true);
521 }
522}
523
524/**
525 * Stop running the PIDController, this sets the output to zero before stopping.
526 */
527void PIDController::Disable() {
528 {
Brian Silverman1a675112016-02-20 20:42:49 -0500529 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500530 m_pidOutput->PIDWrite(0);
531 m_enabled = false;
532 }
533
534 if (m_table != nullptr) {
535 m_table->PutBoolean("enabled", false);
536 }
537}
538
539/**
540 * Return true if PIDController is enabled.
541 */
542bool PIDController::IsEnabled() const {
Brian Silverman1a675112016-02-20 20:42:49 -0500543 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
Brian Silverman26e4e522015-12-17 01:56:40 -0500544 return m_enabled;
545}
546
547/**
548 * Reset the previous error,, the integral term, and disable the controller.
549 */
550void PIDController::Reset() {
551 Disable();
552
Brian Silverman1a675112016-02-20 20:42:49 -0500553 std::lock_guard<priority_recursive_mutex> sync(m_mutex);
554 m_prevError = 0;
Brian Silverman26e4e522015-12-17 01:56:40 -0500555 m_totalError = 0;
556 m_result = 0;
557}
558
559std::string PIDController::GetSmartDashboardType() const {
560 return "PIDController";
561}
562
563void PIDController::InitTable(std::shared_ptr<ITable> table) {
564 if (m_table != nullptr) m_table->RemoveTableListener(this);
565 m_table = table;
566 if (m_table != nullptr) {
567 m_table->PutNumber(kP, GetP());
568 m_table->PutNumber(kI, GetI());
569 m_table->PutNumber(kD, GetD());
570 m_table->PutNumber(kF, GetF());
571 m_table->PutNumber(kSetpoint, GetSetpoint());
572 m_table->PutBoolean(kEnabled, IsEnabled());
573 m_table->AddTableListener(this, false);
574 }
575}
576
577std::shared_ptr<ITable> PIDController::GetTable() const { return m_table; }
578
579void PIDController::ValueChanged(ITable* source, llvm::StringRef key,
580 std::shared_ptr<nt::Value> value, bool isNew) {
581 if (key == kP || key == kI || key == kD || key == kF) {
582 if (m_P != m_table->GetNumber(kP, 0.0) ||
583 m_I != m_table->GetNumber(kI, 0.0) ||
584 m_D != m_table->GetNumber(kD, 0.0) ||
585 m_F != m_table->GetNumber(kF, 0.0)) {
586 SetPID(m_table->GetNumber(kP, 0.0), m_table->GetNumber(kI, 0.0),
587 m_table->GetNumber(kD, 0.0), m_table->GetNumber(kF, 0.0));
588 }
589 } else if (key == kSetpoint && value->IsDouble() &&
590 m_setpoint != value->GetDouble()) {
591 SetSetpoint(value->GetDouble());
592 } else if (key == kEnabled && value->IsBoolean() &&
593 m_enabled != value->GetBoolean()) {
594 if (value->GetBoolean()) {
595 Enable();
596 } else {
597 Disable();
598 }
599 }
600}
601
602void PIDController::UpdateTable() {}
603
604void PIDController::StartLiveWindowMode() { Disable(); }
605
606void PIDController::StopLiveWindowMode() {}