|
36 | 36 | import com.pathplanner.lib.config.PIDConstants; |
37 | 37 | import com.pathplanner.lib.config.RobotConfig; |
38 | 38 | import com.pathplanner.lib.controllers.PPHolonomicDriveController; |
| 39 | + |
39 | 40 | import edu.wpi.first.units.measure.*; |
40 | 41 |
|
41 | 42 | import static edu.wpi.first.units.Units.*; |
42 | 43 |
|
| 44 | +import java.util.Optional; |
| 45 | + |
| 46 | +import org.photonvision.PhotonCamera; |
| 47 | + |
| 48 | +import frc.robot.Constants; |
| 49 | + |
43 | 50 | public class DriveSubsystem extends SubsystemBase { |
44 | 51 |
|
45 | 52 | // Create MAXSwerveModules |
@@ -166,11 +173,13 @@ public Command enableFacePose(Pose2d fixture) { |
166 | 173 | double xFixtureDist = fixture.getX() - robotPose.getX(); |
167 | 174 | double yFixtureDist = fixture.getY() - robotPose.getY(); |
168 | 175 |
|
169 | | - double angleToFixture = Math.atan2(yFixtureDist, xFixtureDist); |
170 | | - |
171 | | - System.out.println(angleToFixture); |
| 176 | + double totalDistance = Math.hypot(xFixtureDist, yFixtureDist); |
172 | 177 |
|
173 | | - m_targetAutoAngle = Radians.of(angleToFixture); |
| 178 | + // Floating point value correction |
| 179 | + if (Math.abs(totalDistance) < Constants.NumericalConstants.kEpsilon) |
| 180 | + return; |
| 181 | + |
| 182 | + m_targetAutoAngle = Radians.of(Math.atan2(yFixtureDist, xFixtureDist)); |
174 | 183 |
|
175 | 184 | m_isManualRotate = false; |
176 | 185 | }); |
@@ -265,10 +274,14 @@ public void resetOdometry(Pose2d pose) { |
265 | 274 | public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) { |
266 | 275 | // Convert the commanded speeds into the correct units for the drivetrain |
267 | 276 |
|
| 277 | + if (!m_isManualRotate) |
| 278 | + System.out.println("Setpoint: " + getOptimalAngle(m_targetAutoAngle, getHeading()).in(Radians) + ", Current: " |
| 279 | + + getHeading().in(Radians)); |
| 280 | + |
268 | 281 | double xSpeedDelivered = xSpeed * DriveConstants.kMaxSpeed.magnitude(); |
269 | 282 | double ySpeedDelivered = ySpeed * DriveConstants.kMaxSpeed.magnitude(); |
270 | 283 | double rotDelivered = (m_isManualRotate) ? rot * DriveConstants.kMaxAngularSpeed.magnitude() |
271 | | - : m_pidController.calculate(getHeading().in(Radians), getOptimalAngle(m_targetAutoAngle).in(Radians)); |
| 284 | + : m_pidController.calculate(getHeading().in(Radians), getOptimalAngle(m_targetAutoAngle, getHeading()).in(Radians)); |
272 | 285 |
|
273 | 286 | var swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates( |
274 | 287 | fieldRelative |
@@ -353,21 +366,23 @@ public Angle getNonContinuousHeading() { |
353 | 366 | return Radians.of(getHeading().in(Radians) - rotations); |
354 | 367 | } |
355 | 368 |
|
356 | | - private Angle getOptimalAngle(Angle target) { |
357 | | - Angle robotHeading = getHeading(); |
358 | | - |
| 369 | + private Angle getOptimalAngle(Angle target, Angle robotHeading) { |
359 | 370 | // Full robot rotations in radians |
360 | | - Angle robotRotations = Radians.of(Radians.convertFrom(Math.floor(robotHeading.in(Radians) / (2 * Math.PI)), Rotations)); |
| 371 | + Angle robotRotations = Radians |
| 372 | + .of(Math.floor(robotHeading.in(Radians) / (2 * Math.PI)) * 2.0 * Math.PI); |
361 | 373 |
|
362 | | - // Both are the same angle, just one is negative and one is positive |
363 | | - Angle pTargetAngle = robotRotations.plus(target); |
364 | | - Angle nTargetAngle = robotRotations.plus(target.minus(Radians.of(2 * Math.PI))); |
| 374 | + Angle wrappedRobotAngle = robotHeading.minus(robotRotations); |
365 | 375 |
|
366 | | - // If either angle is less than 180 degrees relative to the robot's current angle, it is the most optimal path |
367 | | - if (robotHeading.minus(pTargetAngle).abs(Radians) < Math.PI) { |
368 | | - return pTargetAngle; |
369 | | - } |
| 376 | + Angle delta = target.minus(wrappedRobotAngle); |
| 377 | + |
| 378 | + // Ensuring that the angle is always positive to ensure it is wrapped correctly |
| 379 | + if (delta.lt(Radians.of(0.0))) |
| 380 | + delta = delta.plus(Radians.of(2 * Math.PI)); |
| 381 | + |
| 382 | + // Wrapping the delta to make it at most 180 deg |
| 383 | + if (delta.gt(Radians.of(Math.PI))) |
| 384 | + delta = delta.minus(Radians.of(2.0 * Math.PI)); |
370 | 385 |
|
371 | | - return nTargetAngle; |
| 386 | + return delta.plus(robotHeading); |
372 | 387 | } |
373 | 388 | } |
0 commit comments