|
7 | 7 | from commands2 import cmd |
8 | 8 | from wpimath.controller import PIDController, ProfiledPIDControllerRadians |
9 | 9 | from wpimath.geometry import Pose2d, Rotation2d, Translation2d |
10 | | -from wpimath.trajectory import TrajectoryConfig, TrajectoryGenerator |
| 10 | +from wpimath.trajectory import ( |
| 11 | + TrajectoryConfig, |
| 12 | + TrajectoryGenerator, |
| 13 | + TrapezoidProfileRadians, |
| 14 | +) |
| 15 | +from wpimath.controller import ( |
| 16 | + HolonomicDriveController, |
| 17 | + PIDController, |
| 18 | + ProfiledPIDControllerRadians, |
| 19 | +) |
11 | 20 |
|
12 | 21 | from constants import AutoConstants, DriveConstants, OIConstants |
13 | 22 | from subsystems.drivesubsystem import DriveSubsystem |
@@ -88,22 +97,29 @@ def getAutonomousCommand(self) -> commands2.Command: |
88 | 97 | config, |
89 | 98 | ) |
90 | 99 |
|
91 | | - thetaController = ProfiledPIDControllerRadians( |
92 | | - AutoConstants.kPThetaController, |
93 | | - 0, |
94 | | - 0, |
95 | | - AutoConstants.kThetaControllerConstraints, |
| 100 | + # Constraint for the motion profiled robot angle controller |
| 101 | + kThetaControllerConstraints = TrapezoidProfileRadians.Constraints( |
| 102 | + AutoConstants.kMaxAngularSpeedRadiansPerSecond, |
| 103 | + AutoConstants.kMaxAngularSpeedRadiansPerSecondSquared, |
| 104 | + ) |
| 105 | + |
| 106 | + kPXController = PIDController(1.0, 0.0, 0.0) |
| 107 | + kPYController = PIDController(1.0, 0.0, 0.0) |
| 108 | + kPThetaController = ProfiledPIDControllerRadians( |
| 109 | + 1.0, 0.0, 0.0, kThetaControllerConstraints |
| 110 | + ) |
| 111 | + kPThetaController.enableContinuousInput(-math.pi, math.pi) |
| 112 | + |
| 113 | + kPIDController = HolonomicDriveController( |
| 114 | + kPXController, kPYController, kPThetaController |
96 | 115 | ) |
97 | | - thetaController.enableContinuousInput(-math.pi, math.pi) |
98 | 116 |
|
99 | 117 | swerveControllerCommand = commands2.SwerveControllerCommand( |
100 | 118 | exampleTrajectory, |
101 | 119 | self.robotDrive.getPose, # Functional interface to feed supplier |
102 | 120 | DriveConstants.kDriveKinematics, |
103 | 121 | # Position controllers |
104 | | - PIDController(AutoConstants.kPXController, 0, 0), |
105 | | - PIDController(AutoConstants.kPYController, 0, 0), |
106 | | - thetaController, |
| 122 | + kPIDController, |
107 | 123 | self.robotDrive.setModuleStates, |
108 | 124 | (self.robotDrive,), |
109 | 125 | ) |
|
0 commit comments