blob: fdbbb5aac269a4d79e5c19a7facf3d297c915595 [file] [log] [blame]
Brian Silverman26e4e522015-12-17 01:56:40 -05001/*----------------------------------------------------------------------------*/
2/* Copyright (c) FIRST 2008. All Rights Reserved.
3 */
4/* Open Source Software - may be modified and shared by FRC teams. The code */
5/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
6/*----------------------------------------------------------------------------*/
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) {
58 m_controlLoop = std::make_unique<Notifier>(PIDController::CallCalculate, 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
71 static int32_t instances = 0;
72 instances++;
73 HALReport(HALUsageReporting::kResourceType_PIDController, instances);
74}
75
76PIDController::~PIDController() {
77 if (m_table != nullptr) m_table->RemoveTableListener(this);
78}
79
80/**
81 * Call the Calculate method as a non-static method. This avoids having to
82 * prepend
83 * all local variables in that method with the class pointer. This way the
84 * "this"
85 * pointer will be set up and class variables can be called more easily.
86 * This method is static and called by the Notifier class.
87 * @param controller the address of the PID controller object to use in the
88 * background loop
89 */
90void PIDController::CallCalculate(void *controller) {
91 PIDController *control = (PIDController *)controller;
92 control->Calculate();
93}
94
95/**
96 * Read the input, calculate the output accordingly, and write to the output.
97 * This should only be called by the Notifier indirectly through CallCalculate
98 * and is created during initialization.
99 */
100void PIDController::Calculate() {
101 bool enabled;
102 PIDSource *pidInput;
103 PIDOutput *pidOutput;
104
105 {
106 std::lock_guard<priority_mutex> sync(m_mutex);
107 pidInput = m_pidInput;
108 pidOutput = m_pidOutput;
109 enabled = m_enabled;
110 }
111
112 if (pidInput == nullptr) return;
113 if (pidOutput == nullptr) return;
114
115 if (enabled) {
116 std::lock_guard<priority_mutex> sync(m_mutex);
117 float input = pidInput->PIDGet();
118 float result;
119 PIDOutput *pidOutput;
120
121 m_error = m_setpoint - input;
122 if (m_continuous) {
123 if (fabs(m_error) > (m_maximumInput - m_minimumInput) / 2) {
124 if (m_error > 0) {
125 m_error = m_error - m_maximumInput + m_minimumInput;
126 } else {
127 m_error = m_error + m_maximumInput - m_minimumInput;
128 }
129 }
130 }
131
132 if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
133 if (m_P != 0) {
134 double potentialPGain = (m_totalError + m_error) * m_P;
135 if (potentialPGain < m_maximumOutput) {
136 if (potentialPGain > m_minimumOutput)
137 m_totalError += m_error;
138 else
139 m_totalError = m_minimumOutput / m_P;
140 } else {
141 m_totalError = m_maximumOutput / m_P;
142 }
143 }
144
145 m_result = m_D * m_error + m_P * m_totalError + m_setpoint * m_F;
146 }
147 else {
148 if (m_I != 0) {
149 double potentialIGain = (m_totalError + m_error) * m_I;
150 if (potentialIGain < m_maximumOutput) {
151 if (potentialIGain > m_minimumOutput)
152 m_totalError += m_error;
153 else
154 m_totalError = m_minimumOutput / m_I;
155 } else {
156 m_totalError = m_maximumOutput / m_I;
157 }
158 }
159
160 m_result = m_P * m_error + m_I * m_totalError +
161 m_D * (m_prevInput - input) + m_setpoint * m_F;
162 }
163 m_prevInput = input;
164
165 if (m_result > m_maximumOutput)
166 m_result = m_maximumOutput;
167 else if (m_result < m_minimumOutput)
168 m_result = m_minimumOutput;
169
170 pidOutput = m_pidOutput;
171 result = m_result;
172
173 pidOutput->PIDWrite(result);
174
175 // Update the buffer.
176 m_buf.push(m_error);
177 m_bufTotal += m_error;
178 // Remove old elements when buffer is full.
179 if (m_buf.size() > m_bufLength) {
180 m_bufTotal -= m_buf.front();
181 m_buf.pop();
182 }
183 }
184}
185
186/**
187 * Set the PID Controller gain parameters.
188 * Set the proportional, integral, and differential coefficients.
189 * @param p Proportional coefficient
190 * @param i Integral coefficient
191 * @param d Differential coefficient
192 */
193void PIDController::SetPID(double p, double i, double d) {
194 {
195 std::lock_guard<priority_mutex> sync(m_mutex);
196 m_P = p;
197 m_I = i;
198 m_D = d;
199 }
200
201 if (m_table != nullptr) {
202 m_table->PutNumber("p", m_P);
203 m_table->PutNumber("i", m_I);
204 m_table->PutNumber("d", m_D);
205 }
206}
207
208/**
209 * Set the PID Controller gain parameters.
210 * Set the proportional, integral, and differential coefficients.
211 * @param p Proportional coefficient
212 * @param i Integral coefficient
213 * @param d Differential coefficient
214 * @param f Feed forward coefficient
215 */
216void PIDController::SetPID(double p, double i, double d, double f) {
217 {
218 std::lock_guard<priority_mutex> sync(m_mutex);
219 m_P = p;
220 m_I = i;
221 m_D = d;
222 m_F = f;
223 }
224
225 if (m_table != nullptr) {
226 m_table->PutNumber("p", m_P);
227 m_table->PutNumber("i", m_I);
228 m_table->PutNumber("d", m_D);
229 m_table->PutNumber("f", m_F);
230 }
231}
232
233/**
234 * Get the Proportional coefficient
235 * @return proportional coefficient
236 */
237double PIDController::GetP() const {
238 std::lock_guard<priority_mutex> sync(m_mutex);
239 return m_P;
240}
241
242/**
243 * Get the Integral coefficient
244 * @return integral coefficient
245 */
246double PIDController::GetI() const {
247 std::lock_guard<priority_mutex> sync(m_mutex);
248 return m_I;
249}
250
251/**
252 * Get the Differential coefficient
253 * @return differential coefficient
254 */
255double PIDController::GetD() const {
256 std::lock_guard<priority_mutex> sync(m_mutex);
257 return m_D;
258}
259
260/**
261 * Get the Feed forward coefficient
262 * @return Feed forward coefficient
263 */
264double PIDController::GetF() const {
265 std::lock_guard<priority_mutex> sync(m_mutex);
266 return m_F;
267}
268
269/**
270 * Return the current PID result
271 * This is always centered on zero and constrained the the max and min outs
272 * @return the latest calculated output
273 */
274float PIDController::Get() const {
275 std::lock_guard<priority_mutex> sync(m_mutex);
276 return m_result;
277}
278
279/**
280 * Set the PID controller to consider the input to be continuous,
281 * Rather then using the max and min in as constraints, it considers them to
282 * be the same point and automatically calculates the shortest route to
283 * the setpoint.
284 * @param continuous Set to true turns on continuous, false turns off continuous
285 */
286void PIDController::SetContinuous(bool continuous) {
287 std::lock_guard<priority_mutex> sync(m_mutex);
288 m_continuous = continuous;
289}
290
291/**
292 * Sets the maximum and minimum values expected from the input.
293 *
294 * @param minimumInput the minimum value expected from the input
295 * @param maximumInput the maximum value expected from the output
296 */
297void PIDController::SetInputRange(float minimumInput, float maximumInput) {
298 {
299 std::lock_guard<priority_mutex> sync(m_mutex);
300 m_minimumInput = minimumInput;
301 m_maximumInput = maximumInput;
302 }
303
304 SetSetpoint(m_setpoint);
305}
306
307/**
308 * Sets the minimum and maximum values to write.
309 *
310 * @param minimumOutput the minimum value to write to the output
311 * @param maximumOutput the maximum value to write to the output
312 */
313void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) {
314 {
315 std::lock_guard<priority_mutex> sync(m_mutex);
316 m_minimumOutput = minimumOutput;
317 m_maximumOutput = maximumOutput;
318 }
319}
320
321/**
322 * Set the setpoint for the PIDController
323 * Clears the queue for GetAvgError().
324 * @param setpoint the desired setpoint
325 */
326void PIDController::SetSetpoint(float setpoint) {
327 {
328 std::lock_guard<priority_mutex> sync(m_mutex);
329 if (m_maximumInput > m_minimumInput) {
330 if (setpoint > m_maximumInput)
331 m_setpoint = m_maximumInput;
332 else if (setpoint < m_minimumInput)
333 m_setpoint = m_minimumInput;
334 else
335 m_setpoint = setpoint;
336 } else {
337 m_setpoint = setpoint;
338 }
339
340 // Clear m_buf.
341 m_buf = std::queue<double>();
342 }
343
344 if (m_table != nullptr) {
345 m_table->PutNumber("setpoint", m_setpoint);
346 }
347}
348
349/**
350 * Returns the current setpoint of the PIDController
351 * @return the current setpoint
352 */
353double PIDController::GetSetpoint() const {
354 std::lock_guard<priority_mutex> sync(m_mutex);
355 return m_setpoint;
356}
357
358/**
359 * Returns the current difference of the input from the setpoint
360 * @return the current error
361 */
362float PIDController::GetError() const {
363 double pidInput;
364 {
365 std::lock_guard<priority_mutex> sync(m_mutex);
366 pidInput = m_pidInput->PIDGet();
367 }
368 return GetSetpoint() - pidInput;
369}
370
371/**
372 * Sets what type of input the PID controller will use
373 */
374void PIDController::SetPIDSourceType(PIDSourceType pidSource) {
375 m_pidInput->SetPIDSourceType(pidSource);
376}
377/**
378 * Returns the type of input the PID controller is using
379 * @return the PID controller input type
380 */
381PIDSourceType PIDController::GetPIDSourceType() const {
382 return m_pidInput->GetPIDSourceType();
383}
384
385/**
386 * Returns the current average of the error over the past few iterations.
387 * You can specify the number of iterations to average with SetToleranceBuffer()
388 * (defaults to 1). This is the same value that is used for OnTarget().
389 * @return the average error
390 */
391float PIDController::GetAvgError() const {
392 float avgError = 0;
393 {
394 std::lock_guard<priority_mutex> sync(m_mutex);
395 // Don't divide by zero.
396 if (m_buf.size()) avgError = m_bufTotal / m_buf.size();
397 }
398 return avgError;
399}
400
401/*
402 * Set the percentage error which is considered tolerable for use with
403 * OnTarget.
404 * @param percentage error which is tolerable
405 */
406void PIDController::SetTolerance(float percent) {
407 {
408 std::lock_guard<priority_mutex> sync(m_mutex);
409 m_toleranceType = kPercentTolerance;
410 m_tolerance = percent;
411 }
412}
413
414/*
415 * Set the percentage error which is considered tolerable for use with
416 * OnTarget.
417 * @param percentage error which is tolerable
418 */
419void PIDController::SetPercentTolerance(float percent) {
420 {
421 std::lock_guard<priority_mutex> sync(m_mutex);
422 m_toleranceType = kPercentTolerance;
423 m_tolerance = percent;
424 }
425}
426
427/*
428 * Set the absolute error which is considered tolerable for use with
429 * OnTarget.
430 * @param percentage error which is tolerable
431 */
432void PIDController::SetAbsoluteTolerance(float absTolerance) {
433 {
434 std::lock_guard<priority_mutex> sync(m_mutex);
435 m_toleranceType = kAbsoluteTolerance;
436 m_tolerance = absTolerance;
437 }
438}
439
440/*
441 * Set the number of previous error samples to average for tolerancing. When
442 * determining whether a mechanism is on target, the user may want to use a
443 * rolling average of previous measurements instead of a precise position or
444 * velocity. This is useful for noisy sensors which return a few erroneous
445 * measurements when the mechanism is on target. However, the mechanism will
446 * not register as on target for at least the specified bufLength cycles.
447 * @param bufLength Number of previous cycles to average. Defaults to 1.
448 */
449void PIDController::SetToleranceBuffer(unsigned bufLength) {
450 m_bufLength = bufLength;
451
452 // Cut the buffer down to size if needed.
453 while (m_buf.size() > bufLength) {
454 m_bufTotal -= m_buf.front();
455 m_buf.pop();
456 }
457}
458
459/*
460 * Return true if the error is within the percentage of the total input range,
461 * determined by SetTolerance. This asssumes that the maximum and minimum input
462 * were set using SetInput.
463 * Currently this just reports on target as the actual value passes through the
464 * setpoint.
465 * Ideally it should be based on being within the tolerance for some period of
466 * time.
467 */
468bool PIDController::OnTarget() const {
469 double error = GetAvgError();
470
471 std::lock_guard<priority_mutex> sync(m_mutex);
472 switch (m_toleranceType) {
473 case kPercentTolerance:
474 return fabs(error) < m_tolerance / 100 * (m_maximumInput - m_minimumInput);
475 break;
476 case kAbsoluteTolerance:
477 return fabs(error) < m_tolerance;
478 break;
479 case kNoTolerance:
480 // TODO: this case needs an error
481 return false;
482 }
483 return false;
484}
485
486/**
487 * Begin running the PIDController
488 */
489void PIDController::Enable() {
490 {
491 std::lock_guard<priority_mutex> sync(m_mutex);
492 m_enabled = true;
493 }
494
495 if (m_table != nullptr) {
496 m_table->PutBoolean("enabled", true);
497 }
498}
499
500/**
501 * Stop running the PIDController, this sets the output to zero before stopping.
502 */
503void PIDController::Disable() {
504 {
505 std::lock_guard<priority_mutex> sync(m_mutex);
506 m_pidOutput->PIDWrite(0);
507 m_enabled = false;
508 }
509
510 if (m_table != nullptr) {
511 m_table->PutBoolean("enabled", false);
512 }
513}
514
515/**
516 * Return true if PIDController is enabled.
517 */
518bool PIDController::IsEnabled() const {
519 std::lock_guard<priority_mutex> sync(m_mutex);
520 return m_enabled;
521}
522
523/**
524 * Reset the previous error,, the integral term, and disable the controller.
525 */
526void PIDController::Reset() {
527 Disable();
528
529 std::lock_guard<priority_mutex> sync(m_mutex);
530 m_prevInput = 0;
531 m_totalError = 0;
532 m_result = 0;
533}
534
535std::string PIDController::GetSmartDashboardType() const {
536 return "PIDController";
537}
538
539void PIDController::InitTable(std::shared_ptr<ITable> table) {
540 if (m_table != nullptr) m_table->RemoveTableListener(this);
541 m_table = table;
542 if (m_table != nullptr) {
543 m_table->PutNumber(kP, GetP());
544 m_table->PutNumber(kI, GetI());
545 m_table->PutNumber(kD, GetD());
546 m_table->PutNumber(kF, GetF());
547 m_table->PutNumber(kSetpoint, GetSetpoint());
548 m_table->PutBoolean(kEnabled, IsEnabled());
549 m_table->AddTableListener(this, false);
550 }
551}
552
553std::shared_ptr<ITable> PIDController::GetTable() const { return m_table; }
554
555void PIDController::ValueChanged(ITable* source, llvm::StringRef key,
556 std::shared_ptr<nt::Value> value, bool isNew) {
557 if (key == kP || key == kI || key == kD || key == kF) {
558 if (m_P != m_table->GetNumber(kP, 0.0) ||
559 m_I != m_table->GetNumber(kI, 0.0) ||
560 m_D != m_table->GetNumber(kD, 0.0) ||
561 m_F != m_table->GetNumber(kF, 0.0)) {
562 SetPID(m_table->GetNumber(kP, 0.0), m_table->GetNumber(kI, 0.0),
563 m_table->GetNumber(kD, 0.0), m_table->GetNumber(kF, 0.0));
564 }
565 } else if (key == kSetpoint && value->IsDouble() &&
566 m_setpoint != value->GetDouble()) {
567 SetSetpoint(value->GetDouble());
568 } else if (key == kEnabled && value->IsBoolean() &&
569 m_enabled != value->GetBoolean()) {
570 if (value->GetBoolean()) {
571 Enable();
572 } else {
573 Disable();
574 }
575 }
576}
577
578void PIDController::UpdateTable() {}
579
580void PIDController::StartLiveWindowMode() { Disable(); }
581
582void PIDController::StopLiveWindowMode() {}