Skip to content
This repository was archived by the owner on Aug 23, 2025. It is now read-only.

Commit 625f07e

Browse files
committed
Good turn to angle 😋
1 parent b4a7c76 commit 625f07e

File tree

2 files changed

+12
-19
lines changed

2 files changed

+12
-19
lines changed

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

Lines changed: 11 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -172,8 +172,8 @@ public void initDefaultCommands_teleop() {
172172
() -> {
173173
if (swerveDrive.getTurnToAngleMode()) {
174174
return (
175-
driverController.getRightX() > 0.0
176-
|| driverController.getRightY() > 0.0
175+
Math.abs(driverController.getRightX()) > 0.05
176+
|| Math.abs(driverController.getRightY()) > 0.05
177177
);
178178
}
179179
else {
@@ -182,23 +182,16 @@ public void initDefaultCommands_teleop() {
182182
},
183183
// () -> false, // Turn to angle (disabled)
184184
() -> { // Turn To angle Direction
185-
if (Math.abs(driverController.getRightY()) > Math.abs(driverController.getRightX())) {
186-
if (driverController.getRightY() < 0) {
187-
return 0.0;
185+
double xValue = commandDriverController.getRightX();
186+
double yValue = commandDriverController.getRightY();
187+
double magnitude = Math.sqrt((xValue*xValue) + (yValue*yValue));
188+
if (magnitude > 0.49) {
189+
double angle = (90 + NerdyMath.radiansToDegrees(Math.atan2(commandDriverController.getRightY(), commandDriverController.getRightX())));
190+
angle = (((-1 * angle) % 360) + 360) % 360;
191+
SmartDashboard.putNumber("desired angle", angle);
192+
return angle;
188193
}
189-
else if (driverController.getRightY() > 0) {
190-
return 180.0;
191-
}
192-
}
193-
else if ((Math.abs(driverController.getRightY()) < Math.abs(driverController.getRightX()))) {
194-
if (driverController.getRightX() < 0) {
195-
return 90.0;
196-
}
197-
else if (driverController.getRightX() > 0) {
198-
return 270.0;
199-
}
200-
}
201-
return 0.0;
194+
return 1000.0;
202195
});
203196

204197
swerveDrive.setDefaultCommand(swerveJoystickCommand);

src/main/java/frc/robot/subsystems/swerve/SwerveDrivetrain.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -480,7 +480,7 @@ public Command turnToSubwoofer(double angleTolerance) {
480480
return command;
481481
}
482482

483-
public boolean turnToAngleMode = false;
483+
public boolean turnToAngleMode = true;
484484

485485
public Command toggleTurnToAngleMode() {
486486
return Commands.runOnce(() -> turnToAngleMode = !turnToAngleMode);

0 commit comments

Comments
 (0)