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