Skip to content

Commit 04371fe

Browse files
Merge pull request #13 from SubZero-Robotics/bug/face-fixture-wrap
Face fixture wrap fix
2 parents 337fb95 + 9590c17 commit 04371fe

File tree

5 files changed

+52
-20
lines changed

5 files changed

+52
-20
lines changed

.vscode/settings.json

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,5 +57,13 @@
5757
"edu.wpi.first.math.**.proto.*",
5858
"edu.wpi.first.math.**.struct.*",
5959
],
60-
"java.dependency.enableDependencyCheckup": false
60+
"java.dependency.enableDependencyCheckup": false,
61+
"cSpell.words": [
62+
"Deadband",
63+
"feedforwards",
64+
"Holonomic",
65+
"Photonvision",
66+
"Pidgey",
67+
"teleop"
68+
]
6169
}

src/main/java/frc/robot/Constants.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -144,4 +144,8 @@ public static final class VisionConstants {
144144
public static final AprilTagFieldLayout kTagLayout
145145
= AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
146146
}
147+
148+
public static final class NumericalConstants {
149+
public static final double kEpsilon = 1e-6;
150+
}
147151
}
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
package frc.robot;
2+
3+
public class Meters {
4+
5+
}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
import com.pathplanner.lib.commands.PathPlannerAuto;
77

88
import edu.wpi.first.math.MathUtil;
9+
import edu.wpi.first.math.geometry.Pose2d;
910
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
1011
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1112
import edu.wpi.first.wpilibj2.command.Command;
@@ -14,7 +15,6 @@
1415
import frc.robot.Constants.AutoConstants;
1516
import frc.robot.Constants.OIConstants;
1617
import frc.robot.subsystems.DriveSubsystem;
17-
import static edu.wpi.first.units.Units.*;
1818

1919
public class RobotContainer {
2020

@@ -46,7 +46,7 @@ public RobotContainer() {
4646
}
4747

4848
private void configureBindings() {
49-
m_driverController.x().whileTrue(m_drive.moveToAngle(Radians.of(Math.PI)));
49+
m_driverController.x().whileTrue(m_drive.enableFacePose(new Pose2d()));
5050
m_driverController.x().whileFalse(m_drive.disableFacePose());
5151
}
5252

src/main/java/frc/robot/subsystems/DriveSubsystem.java

Lines changed: 32 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -36,10 +36,17 @@
3636
import com.pathplanner.lib.config.PIDConstants;
3737
import com.pathplanner.lib.config.RobotConfig;
3838
import com.pathplanner.lib.controllers.PPHolonomicDriveController;
39+
3940
import edu.wpi.first.units.measure.*;
4041

4142
import static edu.wpi.first.units.Units.*;
4243

44+
import java.util.Optional;
45+
46+
import org.photonvision.PhotonCamera;
47+
48+
import frc.robot.Constants;
49+
4350
public class DriveSubsystem extends SubsystemBase {
4451

4552
// Create MAXSwerveModules
@@ -166,11 +173,13 @@ public Command enableFacePose(Pose2d fixture) {
166173
double xFixtureDist = fixture.getX() - robotPose.getX();
167174
double yFixtureDist = fixture.getY() - robotPose.getY();
168175

169-
double angleToFixture = Math.atan2(yFixtureDist, xFixtureDist);
170-
171-
System.out.println(angleToFixture);
176+
double totalDistance = Math.hypot(xFixtureDist, yFixtureDist);
172177

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));
174183

175184
m_isManualRotate = false;
176185
});
@@ -265,10 +274,14 @@ public void resetOdometry(Pose2d pose) {
265274
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
266275
// Convert the commanded speeds into the correct units for the drivetrain
267276

277+
if (!m_isManualRotate)
278+
System.out.println("Setpoint: " + getOptimalAngle(m_targetAutoAngle, getHeading()).in(Radians) + ", Current: "
279+
+ getHeading().in(Radians));
280+
268281
double xSpeedDelivered = xSpeed * DriveConstants.kMaxSpeed.magnitude();
269282
double ySpeedDelivered = ySpeed * DriveConstants.kMaxSpeed.magnitude();
270283
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));
272285

273286
var swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(
274287
fieldRelative
@@ -353,21 +366,23 @@ public Angle getNonContinuousHeading() {
353366
return Radians.of(getHeading().in(Radians) - rotations);
354367
}
355368

356-
private Angle getOptimalAngle(Angle target) {
357-
Angle robotHeading = getHeading();
358-
369+
private Angle getOptimalAngle(Angle target, Angle robotHeading) {
359370
// 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);
361373

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);
365375

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));
370385

371-
return nTargetAngle;
386+
return delta.plus(robotHeading);
372387
}
373388
}

0 commit comments

Comments
 (0)