Skip to content

Commit 28cb7cf

Browse files
authored
[examples] Add ProfiledPID command to RapidReactCommandBot (#7030)
1 parent dcf5f55 commit 28cb7cf

File tree

7 files changed

+140
-0
lines changed

7 files changed

+140
-0
lines changed

wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66

77
#include <utility>
88

9+
#include <frc/RobotController.h>
910
#include <frc2/command/Commands.h>
1011

1112
Drive::Drive() {
@@ -23,6 +24,14 @@ Drive::Drive() {
2324
// Sets the distance per pulse for the encoders
2425
m_leftEncoder.SetDistancePerPulse(DriveConstants::kEncoderDistancePerPulse);
2526
m_rightEncoder.SetDistancePerPulse(DriveConstants::kEncoderDistancePerPulse);
27+
28+
// Set the controller to be continuous (because it is an angle controller)
29+
m_controller.EnableContinuousInput(-180_deg, 180_deg);
30+
// Set the controller tolerance - the delta tolerance ensures the robot is
31+
// stationary at the setpoint before it is considered as having reached the
32+
// reference
33+
m_controller.SetTolerance(DriveConstants::kTurnTolerance,
34+
DriveConstants::kTurnRateTolerance);
2635
}
2736

2837
frc2::CommandPtr Drive::ArcadeDriveCommand(std::function<double()> fwd,
@@ -50,3 +59,20 @@ frc2::CommandPtr Drive::DriveDistanceCommand(units::meter_t distance,
5059
// Stop the drive when the command ends
5160
.FinallyDo([this](bool interrupted) { m_drive.StopMotor(); });
5261
}
62+
63+
frc2::CommandPtr Drive::TurnToAngleCommand(units::degree_t angle) {
64+
return StartRun(
65+
[this] { m_controller.Reset(m_gyro.GetRotation2d().Degrees()); },
66+
[this, angle] {
67+
m_drive.ArcadeDrive(
68+
0, m_controller.Calculate(m_gyro.GetRotation2d().Degrees(),
69+
angle) +
70+
// Divide feedforward voltage by battery voltage to
71+
// normalize it to [-1, 1]
72+
m_feedforward.Calculate(
73+
m_controller.GetSetpoint().velocity) /
74+
frc::RobotController::GetBatteryVoltage());
75+
})
76+
.Until([this] { return m_controller.AtGoal(); })
77+
.FinallyDo([this] { m_drive.ArcadeDrive(0, 0); });
78+
}

wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,23 @@ inline constexpr double kEncoderDistancePerPulse =
2929
// Assumes the encoders are directly mounted on the wheel shafts
3030
((kWheelDiameter * std::numbers::pi) / kEncoderCPR).value();
3131

32+
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
33+
// These values MUST be determined either experimentally or theoretically for
34+
// *your* robot's drive. The SysId tool provides a convenient method for
35+
// obtaining feedback and feedforward values for your robot.
36+
inline constexpr double kTurnP = 1;
37+
inline constexpr double kTurnI = 0;
38+
inline constexpr double kTurnD = 0;
39+
40+
inline constexpr auto kTurnTolerance = 5_deg;
41+
inline constexpr auto kTurnRateTolerance = 10_deg_per_s;
42+
43+
inline constexpr auto kMaxTurnRate = 100_deg_per_s;
44+
inline constexpr auto kMaxTurnAcceleration = 300_deg_per_s / 1_s;
45+
46+
inline constexpr auto ks = 1_V;
47+
inline constexpr auto kv = 0.8_V * 1_s / 1_deg;
48+
inline constexpr auto ka = 0.15_V * 1_s * 1_s / 1_deg;
3249
} // namespace DriveConstants
3350

3451
namespace IntakeConstants {

wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,11 +6,15 @@
66

77
#include <functional>
88

9+
#include <frc/ADXRS450_Gyro.h>
910
#include <frc/Encoder.h>
11+
#include <frc/controller/ProfiledPIDController.h>
12+
#include <frc/controller/SimpleMotorFeedforward.h>
1013
#include <frc/drive/DifferentialDrive.h>
1114
#include <frc/motorcontrol/PWMSparkMax.h>
1215
#include <frc2/command/CommandPtr.h>
1316
#include <frc2/command/SubsystemBase.h>
17+
#include <units/angle.h>
1418
#include <units/length.h>
1519

1620
#include "Constants.h"
@@ -38,6 +42,15 @@ class Drive : public frc2::SubsystemBase {
3842
[[nodiscard]]
3943
frc2::CommandPtr DriveDistanceCommand(units::meter_t distance, double speed);
4044

45+
/**
46+
* Returns a command that turns to robot to the specified angle using a motion
47+
* profile and PID controller.
48+
*
49+
* @param angle The angle to turn to
50+
*/
51+
[[nodiscard]]
52+
frc2::CommandPtr TurnToAngleCommand(units::degree_t angle);
53+
4154
private:
4255
frc::PWMSparkMax m_leftLeader{DriveConstants::kLeftMotor1Port};
4356
frc::PWMSparkMax m_leftFollower{DriveConstants::kLeftMotor2Port};
@@ -54,4 +67,14 @@ class Drive : public frc2::SubsystemBase {
5467
frc::Encoder m_rightEncoder{DriveConstants::kRightEncoderPorts[0],
5568
DriveConstants::kRightEncoderPorts[1],
5669
DriveConstants::kRightEncoderReversed};
70+
71+
frc::ADXRS450_Gyro m_gyro;
72+
73+
frc::ProfiledPIDController<units::radians> m_controller{
74+
DriveConstants::kTurnP,
75+
DriveConstants::kTurnI,
76+
DriveConstants::kTurnD,
77+
{DriveConstants::kMaxTurnRate, DriveConstants::kMaxTurnAcceleration}};
78+
frc::SimpleMotorFeedforward<units::radians> m_feedforward{
79+
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka};
5780
};

wpilibcExamples/src/main/cpp/examples/examples.json

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -394,6 +394,8 @@
394394
"Pneumatics",
395395
"Digital Input",
396396
"PID",
397+
"Gyro",
398+
"Profiled PID",
397399
"XboxController"
398400
],
399401
"foldername": "RapidReactCommandBot",

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -388,6 +388,8 @@
388388
"Pneumatics",
389389
"Digital Input",
390390
"PID",
391+
"Gyro",
392+
"Profiled PID",
391393
"XboxController"
392394
],
393395
"foldername": "rapidreactcommandbot",

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,24 @@ public static final class DriveConstants {
3131
public static final double kEncoderDistancePerPulse =
3232
// Assumes the encoders are directly mounted on the wheel shafts
3333
(kWheelDiameterMeters * Math.PI) / kEncoderCPR;
34+
35+
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
36+
// These values MUST be determined either experimentally or theoretically for *your* robot's
37+
// drive. The SysId tool provides a convenient method for obtaining feedback and feedforward
38+
// values for your robot.
39+
public static final double kTurnP = 1;
40+
public static final double kTurnI = 0;
41+
public static final double kTurnD = 0;
42+
43+
public static final double kTurnToleranceDeg = 5;
44+
public static final double kTurnRateToleranceDegPerS = 10; // degrees per second
45+
46+
public static final double kMaxTurnRateDegPerS = 100;
47+
public static final double kMaxTurnAccelerationDegPerSSquared = 300;
48+
49+
public static final double ksVolts = 1;
50+
public static final double kvVoltSecondsPerDegree = 0.8;
51+
public static final double kaVoltSecondsSquaredPerDegree = 0.15;
3452
}
3553

3654
public static final class ShooterConstants {

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,18 @@
44

55
package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
66

7+
import static edu.wpi.first.units.Units.DegreesPerSecond;
8+
import static edu.wpi.first.units.Units.Volts;
9+
710
import edu.wpi.first.epilogue.Logged;
811
import edu.wpi.first.epilogue.NotLogged;
12+
import edu.wpi.first.math.controller.ProfiledPIDController;
13+
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
14+
import edu.wpi.first.math.trajectory.TrapezoidProfile;
915
import edu.wpi.first.util.sendable.SendableRegistry;
16+
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
1017
import edu.wpi.first.wpilibj.Encoder;
18+
import edu.wpi.first.wpilibj.RobotController;
1119
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
1220
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConstants;
1321
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
@@ -44,6 +52,21 @@ public class Drive extends SubsystemBase {
4452
DriveConstants.kRightEncoderPorts[1],
4553
DriveConstants.kRightEncoderReversed);
4654

55+
private final ADXRS450_Gyro m_gyro = new ADXRS450_Gyro();
56+
private final ProfiledPIDController m_controller =
57+
new ProfiledPIDController(
58+
DriveConstants.kTurnP,
59+
DriveConstants.kTurnI,
60+
DriveConstants.kTurnD,
61+
new TrapezoidProfile.Constraints(
62+
DriveConstants.kMaxTurnRateDegPerS,
63+
DriveConstants.kMaxTurnAccelerationDegPerSSquared));
64+
private final SimpleMotorFeedforward m_feedforward =
65+
new SimpleMotorFeedforward(
66+
DriveConstants.ksVolts,
67+
DriveConstants.kvVoltSecondsPerDegree,
68+
DriveConstants.kaVoltSecondsSquaredPerDegree);
69+
4770
/** Creates a new Drive subsystem. */
4871
public Drive() {
4972
SendableRegistry.addChild(m_drive, m_leftLeader);
@@ -60,6 +83,13 @@ public Drive() {
6083
// Sets the distance per pulse for the encoders
6184
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
6285
m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
86+
87+
// Set the controller to be continuous (because it is an angle controller)
88+
m_controller.enableContinuousInput(-180, 180);
89+
// Set the controller tolerance - the delta tolerance ensures the robot is stationary at the
90+
// setpoint before it is considered as having reached the reference
91+
m_controller.setTolerance(
92+
DriveConstants.kTurnToleranceDeg, DriveConstants.kTurnRateToleranceDegPerS);
6393
}
6494

6595
/**
@@ -98,4 +128,26 @@ public Command driveDistanceCommand(double distanceMeters, double speed) {
98128
// Stop the drive when the command ends
99129
.finallyDo(interrupted -> m_drive.stopMotor());
100130
}
131+
132+
/**
133+
* Returns a command that turns to robot to the specified angle using a motion profile and PID
134+
* controller.
135+
*
136+
* @param angleDeg The angle to turn to
137+
*/
138+
public Command turnToAngleCommand(double angleDeg) {
139+
return startRun(
140+
() -> m_controller.reset(m_gyro.getRotation2d().getDegrees()),
141+
() ->
142+
m_drive.arcadeDrive(
143+
0,
144+
m_controller.calculate(m_gyro.getRotation2d().getDegrees(), angleDeg)
145+
// Divide feedforward voltage by battery voltage to normalize it to [-1, 1]
146+
+ m_feedforward
147+
.calculate(DegreesPerSecond.of(m_controller.getSetpoint().velocity))
148+
.in(Volts)
149+
/ RobotController.getBatteryVoltage()))
150+
.until(m_controller::atGoal)
151+
.finallyDo(() -> m_drive.arcadeDrive(0, 0));
152+
}
101153
}

0 commit comments

Comments
 (0)