Add replacement PIDController class (#1300)

Originally, PIDController used PIDSource with its "PIDSourceType" to
determine whether a class should return position or velocity to the
controller. However, the supported languages have changed a lot over 10
years and now support lambdas. Instead of using PIDSource and PIDOutput,
users can pass in doubles to the Calculate() function synchronously.
This makes the controller much more flexible for team's needs as they no
longer have to make a separate PIDSource-inheriting class just to
provide a custom input.

The built-in feedforward was removed. Since PIDController is synchronous
now, they can add their own feedforward on top of what Calculate()
returns.

To facilitate running the controller asynchronously, there is a
PIDControllerRunner class that handles that. By separating the loop from
the control law, PIDController can now be composed with others and be
used to control a drivetrain (a multiple input, multiple output system
that requires summing the results from two controllers) much easier.
Also, motion profiling can be used to set the reference over time.

All the classes related to the old PIDController are now deprecated. The
new classes are in an experimental namespace to avoid name conflicts.

While this is a large change, I think it is a necessary one for growth.
The old PIDController design was created in a time when languages only
supported OOP, and we have more tools at our disposal now to solve
problems. This more versatile implementation can be used in more places
like as a replacement for Pathfinder's "EncoderFollower" class.

There has been hesitation to add lambda support to WPILib for a while
now out of concerns for requiring teams to learn more features of C++ or
Java. In my opinion, this change makes PIDController easier to use, not
harder. The concept of a function is a building block of OOP and should
be learned before classes. The ability to store functions as first-class
objects and invoke them just like variables is rather natural.

Note that PID constants for the new controller will be different from
the old one. The original controller didn't take the discretization
period into account. To fix this, teams should just have to divide their
Ki gain by 0.05 and multiply their Kd gain by 0.05 where 0.05 is the
original default period.
This commit is contained in:
Tyler Veness
2019-07-07 15:37:13 -07:00
committed by Peter Johnson
parent 9b798d228f
commit ea9512977c
20 changed files with 1773 additions and 161 deletions

View File

@@ -0,0 +1,87 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;
import edu.wpi.first.wpilibj.controller.PIDController;
import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertTrue;
class PIDInputOutputTest {
private PIDController m_controller;
@BeforeEach
void setUp() {
m_controller = new PIDController(0, 0, 0);
}
@Test
void outputRangeTest() {
m_controller.setP(1);
m_controller.setOutputRange(-50, 50);
assertAll(
() -> assertEquals(-50, m_controller.calculate(100, 0), 1e-5),
() -> assertEquals(50, m_controller.calculate(0, 100), 1e-5)
);
}
@Test
void inputRangeTest() {
m_controller.setP(1);
m_controller.setOutputRange(-1000, 1000);
m_controller.setInputRange(-50, 50);
assertAll(
() -> assertEquals(-100, m_controller.calculate(100, 0), 1e-5),
() -> assertEquals(50, m_controller.calculate(0, 100), 1e-5)
);
}
@Test
void continuousInputTest() {
m_controller.setP(1);
m_controller.setInputRange(-180, 180);
m_controller.setContinuous(true);
assertTrue(m_controller.calculate(-179, 179) < 0.0);
}
@Test
void proportionalGainOutputTest() {
m_controller.setP(4);
assertEquals(-0.1, m_controller.calculate(0.025, 0), 1e-5);
}
@Test
void integralGainOutputTest() {
m_controller.setI(4);
double out = 0;
for (int i = 0; i < 5; i++) {
out = m_controller.calculate(.025, 0);
}
assertEquals(-0.5 * m_controller.getPeriod(), out, 1e-5);
}
@Test
void derivativeGainOutputTest() {
m_controller.setD(4);
m_controller.calculate(0, 0);
assertEquals(-0.01 / m_controller.getPeriod(), m_controller.calculate(0.0025, 0), 1e-5);
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */
/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -11,93 +11,92 @@ import org.junit.jupiter.api.AfterEach;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.PIDControllerRunner;
import static org.junit.jupiter.api.Assertions.assertFalse;
import static org.junit.jupiter.api.Assertions.assertTrue;
class PIDToleranceTest {
private PIDController m_pid;
private static final double m_setPoint = 50.0;
private PIDController m_pidController;
private PIDControllerRunner m_pidRunner;
private static final double m_setpoint = 50.0;
private static final double m_tolerance = 10.0;
private static final double m_range = 200;
private class FakeInput implements PIDSource {
private static class FakeInput {
public double m_val;
FakeInput() {
m_val = 0;
}
@Override
public PIDSourceType getPIDSourceType() {
return PIDSourceType.kDisplacement;
}
@Override
public double pidGet() {
public double getMeasurement() {
return m_val;
}
@Override
public void setPIDSourceType(PIDSourceType arg0) {
}
}
private FakeInput m_inp;
private final PIDOutput m_out = new PIDOutput() {
@Override
public void pidWrite(double out) {
}
};
@BeforeEach
void setUp() {
m_inp = new FakeInput();
m_pid = new PIDController(0.05, 0.0, 0.0, m_inp, m_out);
m_pid.setInputRange(-m_range / 2, m_range / 2);
m_pidController = new PIDController(0.05, 0.0, 0.0);
m_pidRunner = new PIDControllerRunner(m_pidController, m_inp::getMeasurement, x -> { });
m_pidController.setInputRange(-m_range / 2, m_range / 2);
}
@AfterEach
void tearDown() {
m_pid.close();
m_pid = null;
m_pidController.close();
m_pidController = null;
}
@Test
void initialToleranceTest() {
assertFalse(m_pidController.atSetpoint());
}
@Test
void absoluteToleranceTest() {
m_pid.setAbsoluteTolerance(m_tolerance);
m_pid.setSetpoint(m_setPoint);
m_pid.enable();
m_pidController.setAbsoluteTolerance(m_tolerance);
m_pidController.setSetpoint(m_setpoint);
m_pidRunner.enable();
Timer.delay(1);
assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+ m_pid.getError());
m_inp.m_val = m_setPoint + m_tolerance / 2;
assertFalse(m_pidController.atSetpoint(),
"Error was in tolerance when it should not have been. Error was "
+ m_pidController.getError());
m_inp.m_val = m_setpoint + m_tolerance / 2;
Timer.delay(1.0);
assertTrue(m_pid.onTarget(), "Error was not in tolerance when it should have been. Error was "
+ m_pid.getError());
m_inp.m_val = m_setPoint + 10 * m_tolerance;
assertTrue(m_pidController.atSetpoint(),
"Error was not in tolerance when it should have been. Error was "
+ m_pidController.getError());
m_inp.m_val = m_setpoint + 10 * m_tolerance;
Timer.delay(1.0);
assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+ m_pid.getError());
assertFalse(m_pidController.atSetpoint(),
"Error was in tolerance when it should not have been. Error was "
+ m_pidController.getError());
}
@Test
void percentToleranceTest() {
m_pid.setPercentTolerance(m_tolerance);
m_pid.setSetpoint(m_setPoint);
m_pid.enable();
assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+ m_pid.getError());
m_pidController.setPercentTolerance(m_tolerance);
m_pidController.setSetpoint(m_setpoint);
m_pidRunner.enable();
assertFalse(m_pidController.atSetpoint(),
"Error was in tolerance when it should not have been. Error was "
+ m_pidController.getError());
//half of percent tolerance away from setPoint
m_inp.m_val = m_setPoint + m_tolerance / 200 * m_range;
m_inp.m_val = m_setpoint + m_tolerance / 200 * m_range;
Timer.delay(1.0);
assertTrue(m_pid.onTarget(), "Error was not in tolerance when it should have been. Error was "
+ m_pid.getError());
assertTrue(m_pidController.atSetpoint(),
"Error was not in tolerance when it should have been. Error was "
+ m_pidController.getError());
//double percent tolerance away from setPoint
m_inp.m_val = m_setPoint + m_tolerance / 50 * m_range;
m_inp.m_val = m_setpoint + m_tolerance / 50 * m_range;
Timer.delay(1.0);
assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+ m_pid.getError());
assertFalse(m_pidController.atSetpoint(),
"Error was in tolerance when it should not have been. Error was "
+ m_pidController.getError());
}
}