2020-12-26 14:12:05 -08:00
|
|
|
// Copyright (c) FIRST and other WPILib contributors.
|
|
|
|
|
// Open Source Software; you can modify and/or share it under the terms of
|
|
|
|
|
// the WPILib BSD license file in the root directory of this project.
|
2014-06-07 17:37:51 -04:00
|
|
|
|
2019-11-26 01:00:35 -05:00
|
|
|
#include <algorithm>
|
|
|
|
|
|
2023-08-28 15:13:34 -07:00
|
|
|
#include <gtest/gtest.h>
|
2021-05-28 22:06:59 -07:00
|
|
|
#include <units/time.h>
|
|
|
|
|
|
2016-05-25 22:38:11 -07:00
|
|
|
#include "TestBench.h"
|
2018-07-20 00:03:45 -07:00
|
|
|
#include "frc/Encoder.h"
|
2019-08-04 03:01:11 -04:00
|
|
|
#include "frc/Notifier.h"
|
2018-07-20 00:03:45 -07:00
|
|
|
#include "frc/Timer.h"
|
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.
2019-07-07 15:37:13 -07:00
|
|
|
#include "frc/controller/PIDController.h"
|
2021-06-08 21:21:01 -07:00
|
|
|
#include "frc/filter/LinearFilter.h"
|
2021-04-17 11:27:16 -07:00
|
|
|
#include "frc/motorcontrol/Jaguar.h"
|
|
|
|
|
#include "frc/motorcontrol/Talon.h"
|
|
|
|
|
#include "frc/motorcontrol/Victor.h"
|
2016-05-25 22:38:11 -07:00
|
|
|
|
2014-06-07 17:37:51 -04:00
|
|
|
enum MotorEncoderTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON };
|
|
|
|
|
|
2016-05-20 17:30:37 -07:00
|
|
|
std::ostream& operator<<(std::ostream& os, MotorEncoderTestType const& type) {
|
2015-06-25 15:07:55 -04:00
|
|
|
switch (type) {
|
|
|
|
|
case TEST_VICTOR:
|
|
|
|
|
os << "Victor";
|
|
|
|
|
break;
|
|
|
|
|
case TEST_JAGUAR:
|
|
|
|
|
os << "Jaguar";
|
|
|
|
|
break;
|
|
|
|
|
case TEST_TALON:
|
|
|
|
|
os << "Talon";
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return os;
|
2014-06-07 17:37:51 -04:00
|
|
|
}
|
|
|
|
|
|
2021-05-28 22:06:59 -07:00
|
|
|
static constexpr auto kMotorTime = 0.5_s;
|
2014-06-07 17:37:51 -04:00
|
|
|
|
|
|
|
|
/**
|
2021-04-17 11:27:16 -07:00
|
|
|
* A fixture that includes a PWM motor controller and an encoder connected to
|
2014-06-07 17:37:51 -04:00
|
|
|
* the same motor.
|
|
|
|
|
*/
|
|
|
|
|
class MotorEncoderTest : public testing::TestWithParam<MotorEncoderTestType> {
|
2015-06-25 15:07:55 -04:00
|
|
|
protected:
|
2021-05-31 10:21:34 -07:00
|
|
|
frc::MotorController* m_motorController;
|
|
|
|
|
frc::Encoder* m_encoder;
|
|
|
|
|
frc::LinearFilter<double>* m_filter;
|
2015-06-25 15:07:55 -04:00
|
|
|
|
2021-05-31 10:21:34 -07:00
|
|
|
MotorEncoderTest() {
|
2015-06-25 15:07:55 -04:00
|
|
|
switch (GetParam()) {
|
|
|
|
|
case TEST_VICTOR:
|
2021-05-31 10:21:34 -07:00
|
|
|
m_motorController = new frc::Victor(TestBench::kVictorChannel);
|
|
|
|
|
m_encoder = new frc::Encoder(TestBench::kVictorEncoderChannelA,
|
|
|
|
|
TestBench::kVictorEncoderChannelB);
|
2015-06-25 15:07:55 -04:00
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
case TEST_JAGUAR:
|
2021-05-31 10:21:34 -07:00
|
|
|
m_motorController = new frc::Jaguar(TestBench::kJaguarChannel);
|
|
|
|
|
m_encoder = new frc::Encoder(TestBench::kJaguarEncoderChannelA,
|
|
|
|
|
TestBench::kJaguarEncoderChannelB);
|
2015-06-25 15:07:55 -04:00
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
case TEST_TALON:
|
2021-05-31 10:21:34 -07:00
|
|
|
m_motorController = new frc::Talon(TestBench::kTalonChannel);
|
|
|
|
|
m_encoder = new frc::Encoder(TestBench::kTalonEncoderChannelA,
|
|
|
|
|
TestBench::kTalonEncoderChannelB);
|
2015-06-25 15:07:55 -04:00
|
|
|
break;
|
|
|
|
|
}
|
2021-05-31 10:21:34 -07:00
|
|
|
m_filter = new frc::LinearFilter<double>(
|
|
|
|
|
frc::LinearFilter<double>::MovingAverage(50));
|
2015-06-25 15:07:55 -04:00
|
|
|
}
|
|
|
|
|
|
2021-05-31 10:21:34 -07:00
|
|
|
~MotorEncoderTest() {
|
2017-12-04 20:05:02 -08:00
|
|
|
delete m_filter;
|
2021-05-31 10:21:34 -07:00
|
|
|
delete m_encoder;
|
|
|
|
|
delete m_motorController;
|
2015-06-25 15:07:55 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void Reset() {
|
2021-04-17 11:27:16 -07:00
|
|
|
m_motorController->Set(0.0);
|
2015-06-25 15:07:55 -04:00
|
|
|
m_encoder->Reset();
|
2017-12-04 20:05:02 -08:00
|
|
|
m_filter->Reset();
|
2015-06-25 15:07:55 -04:00
|
|
|
}
|
2014-06-07 17:37:51 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Test if the encoder value increments after the motor drives forward
|
|
|
|
|
*/
|
|
|
|
|
TEST_P(MotorEncoderTest, Increment) {
|
2015-06-25 15:07:55 -04:00
|
|
|
Reset();
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2021-04-17 11:27:16 -07:00
|
|
|
/* Drive the motor controller briefly to move the encoder */
|
|
|
|
|
m_motorController->Set(0.2f);
|
2021-05-31 10:21:34 -07:00
|
|
|
frc::Wait(kMotorTime);
|
2021-04-17 11:27:16 -07:00
|
|
|
m_motorController->Set(0.0);
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2015-06-25 15:07:55 -04:00
|
|
|
/* The encoder should be positive now */
|
|
|
|
|
EXPECT_GT(m_encoder->Get(), 0)
|
|
|
|
|
<< "Encoder should have incremented after the motor moved";
|
2014-06-07 17:37:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Test if the encoder value decrements after the motor drives backwards
|
|
|
|
|
*/
|
|
|
|
|
TEST_P(MotorEncoderTest, Decrement) {
|
2015-06-25 15:07:55 -04:00
|
|
|
Reset();
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2021-04-17 11:27:16 -07:00
|
|
|
/* Drive the motor controller briefly to move the encoder */
|
|
|
|
|
m_motorController->Set(-0.2);
|
2021-05-31 10:21:34 -07:00
|
|
|
frc::Wait(kMotorTime);
|
2021-04-17 11:27:16 -07:00
|
|
|
m_motorController->Set(0.0);
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2015-06-25 15:07:55 -04:00
|
|
|
/* The encoder should be positive now */
|
2016-11-20 07:25:03 -08:00
|
|
|
EXPECT_LT(m_encoder->Get(), 0.0)
|
2015-06-25 15:07:55 -04:00
|
|
|
<< "Encoder should have decremented after the motor moved";
|
2014-06-07 17:37:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Test if motor speeds are clamped to [-1,1]
|
|
|
|
|
*/
|
|
|
|
|
TEST_P(MotorEncoderTest, ClampSpeed) {
|
2015-06-25 15:07:55 -04:00
|
|
|
Reset();
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2021-04-17 11:27:16 -07:00
|
|
|
m_motorController->Set(2.0);
|
2021-05-31 10:21:34 -07:00
|
|
|
frc::Wait(kMotorTime);
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2021-04-17 11:27:16 -07:00
|
|
|
EXPECT_FLOAT_EQ(1.0, m_motorController->Get());
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2021-04-17 11:27:16 -07:00
|
|
|
m_motorController->Set(-2.0);
|
2021-05-31 10:21:34 -07:00
|
|
|
frc::Wait(kMotorTime);
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2021-04-17 11:27:16 -07:00
|
|
|
EXPECT_FLOAT_EQ(-1.0, m_motorController->Get());
|
2014-06-07 17:37:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
2015-07-14 20:37:52 -07:00
|
|
|
* Test if position PID loop works
|
2014-06-07 17:37:51 -04:00
|
|
|
*/
|
2015-07-14 20:37:52 -07:00
|
|
|
TEST_P(MotorEncoderTest, PositionPIDController) {
|
2015-06-25 15:07:55 -04:00
|
|
|
Reset();
|
2016-01-28 14:25:39 -05:00
|
|
|
double goal = 1000;
|
2023-09-15 19:57:31 -07:00
|
|
|
frc::PIDController pidController(0.001, 0.01, 0.0);
|
2019-08-25 13:01:51 -07:00
|
|
|
pidController.SetTolerance(50.0);
|
2019-08-26 21:40:30 -07:00
|
|
|
pidController.SetIntegratorRange(-0.2, 0.2);
|
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.
2019-07-07 15:37:13 -07:00
|
|
|
pidController.SetSetpoint(goal);
|
|
|
|
|
|
|
|
|
|
/* 10 seconds should be plenty time to get to the reference */
|
2019-08-04 03:01:11 -04:00
|
|
|
frc::Notifier pidRunner{[this, &pidController] {
|
2019-11-26 01:00:35 -05:00
|
|
|
auto speed = pidController.Calculate(m_encoder->GetDistance());
|
2021-04-17 11:27:16 -07:00
|
|
|
m_motorController->Set(std::clamp(speed, -0.2, 0.2));
|
2019-08-04 03:01:11 -04:00
|
|
|
}};
|
|
|
|
|
pidRunner.StartPeriodic(pidController.GetPeriod());
|
2021-05-31 10:21:34 -07:00
|
|
|
frc::Wait(10_s);
|
2019-08-04 03:01:11 -04:00
|
|
|
pidRunner.Stop();
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2019-08-14 22:17:44 -07:00
|
|
|
RecordProperty("PIDError", pidController.GetPositionError());
|
2014-08-15 11:22:01 -04:00
|
|
|
|
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.
2019-07-07 15:37:13 -07:00
|
|
|
EXPECT_TRUE(pidController.AtSetpoint())
|
2016-05-20 17:30:37 -07:00
|
|
|
<< "PID loop did not converge within 10 seconds. Goal was: " << goal
|
2019-08-14 22:17:44 -07:00
|
|
|
<< " Error was: " << pidController.GetPositionError();
|
2014-06-07 17:37:51 -04:00
|
|
|
}
|
|
|
|
|
|
2015-07-14 20:37:52 -07:00
|
|
|
/**
|
|
|
|
|
* Test if velocity PID loop works
|
|
|
|
|
*/
|
|
|
|
|
TEST_P(MotorEncoderTest, VelocityPIDController) {
|
|
|
|
|
Reset();
|
|
|
|
|
|
2023-09-15 19:57:31 -07:00
|
|
|
frc::PIDController pidController(1e-5, 0.0, 0.0006);
|
2019-08-25 13:01:51 -07:00
|
|
|
pidController.SetTolerance(200.0);
|
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.
2019-07-07 15:37:13 -07:00
|
|
|
pidController.SetSetpoint(600);
|
|
|
|
|
|
|
|
|
|
/* 10 seconds should be plenty time to get to the reference */
|
2019-08-04 03:01:11 -04:00
|
|
|
frc::Notifier pidRunner{[this, &pidController] {
|
2019-11-26 01:00:35 -05:00
|
|
|
auto speed =
|
|
|
|
|
pidController.Calculate(m_filter->Calculate(m_encoder->GetRate()));
|
2021-04-17 11:27:16 -07:00
|
|
|
m_motorController->Set(std::clamp(speed, -0.3, 0.3));
|
2019-08-04 03:01:11 -04:00
|
|
|
}};
|
|
|
|
|
pidRunner.StartPeriodic(pidController.GetPeriod());
|
2021-05-31 10:21:34 -07:00
|
|
|
frc::Wait(10_s);
|
2019-08-04 03:01:11 -04:00
|
|
|
pidRunner.Stop();
|
2019-08-14 22:17:44 -07:00
|
|
|
RecordProperty("PIDError", pidController.GetPositionError());
|
2016-01-28 14:25:39 -05:00
|
|
|
|
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.
2019-07-07 15:37:13 -07:00
|
|
|
EXPECT_TRUE(pidController.AtSetpoint())
|
2016-05-20 17:30:37 -07:00
|
|
|
<< "PID loop did not converge within 10 seconds. Goal was: " << 600
|
2019-08-14 22:17:44 -07:00
|
|
|
<< " Error was: " << pidController.GetPositionError();
|
2015-07-14 20:37:52 -07:00
|
|
|
}
|
|
|
|
|
|
2014-06-07 17:37:51 -04:00
|
|
|
/**
|
|
|
|
|
* Test resetting encoders
|
|
|
|
|
*/
|
|
|
|
|
TEST_P(MotorEncoderTest, Reset) {
|
2015-06-25 15:07:55 -04:00
|
|
|
Reset();
|
2014-08-15 11:22:01 -04:00
|
|
|
|
2015-06-25 15:07:55 -04:00
|
|
|
EXPECT_EQ(0, m_encoder->Get()) << "Encoder did not reset to 0";
|
2014-06-07 17:37:51 -04:00
|
|
|
}
|
|
|
|
|
|
2021-09-21 06:12:50 -07:00
|
|
|
INSTANTIATE_TEST_SUITE_P(Tests, MotorEncoderTest,
|
2019-05-31 13:43:32 -07:00
|
|
|
testing::Values(TEST_VICTOR, TEST_JAGUAR, TEST_TALON));
|