Skip to content

Commit

Permalink
[#475] - some more formatting and constant changes
Browse files Browse the repository at this point in the history
  • Loading branch information
HeeistHo committed Apr 2, 2024
1 parent 06fbd8e commit f9dc5f3
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 7 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -356,7 +356,7 @@ public class VisionConstants {
Units.feetToMeters(26.0));
public static final Translation2d VISION_LIMIT = new Translation2d(Units.feetToMeters(9),
Units.feetToMeters(5));
public static final double ALIGNMENT_TOLERANCE = 8d; // TODO: make this an actual value
public static final double ALIGNMENT_TOLERANCE = 3d; // TODO: make this an actual value
public static final double POINTATTAG_ALIGNMENT_TOLERANCE = 1d;
public static final PIDController POINT_AIM_CONTROLLER = new PIDController(0.2, 0, 0.015, 0.01);
public static final PIDController TAG_AIM_CONTROLLER = new PIDController(0.1, 0, 0.01);
Expand Down
13 changes: 7 additions & 6 deletions src/main/java/frc/robot/command/ChasePieces.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ public class ChasePieces extends Command {
private double collectPower;
private double maxCollectPower;
private double drivePower;
private double slowDrive = 0.5d;
private double rotPower;

private Pose2d startingPose;
Expand Down Expand Up @@ -209,15 +210,15 @@ private void autoChase(){
if (!hasSeenTarget) {
if (startingPose.getY() > VisionConstants.HALF_FIELD_HEIGHT) {
if (DriverStation.getAlliance().get() == Alliance.Blue) {
drivetrain.setRobot(0.5, 0, -rotPower);
drivetrain.setRobot(slowDrive, 0, -rotPower);
} else {
drivetrain.setRobot(0.5, 0, rotPower);
drivetrain.setRobot(slowDrive, 0, rotPower);
}
} else {
if (DriverStation.getAlliance().get() == Alliance.Blue) {
drivetrain.setRobot(0.5, 0, rotPower);
drivetrain.setRobot(slowDrive, 0, rotPower);
} else {
drivetrain.setRobot(0.5, 0, -rotPower);
drivetrain.setRobot(slowDrive, 0, -rotPower);
}
}
} else {
Expand Down Expand Up @@ -284,11 +285,11 @@ public boolean trustValues() {
public boolean isFinished() {
if (DriverStation.isAutonomous()) {
if (DriverStation.getAlliance().get() == Alliance.Blue) {
if (drivetrain.getPose().getX() > AutonomousConstants.CHASE_BOUNDARY) {
if (drivetrain.getPose().getX() > AutonomousConstants.BLUE_CHASE_BOUNDARY) {
return true;
}
} else {
if (drivetrain.getPose().getX() < AutonomousConstants.CHASE_BOUNDARY) {
if (drivetrain.getPose().getX() < AutonomousConstants.RED_CHASE_BOUNDARY) {
return true;
}
}
Expand Down

0 comments on commit f9dc5f3

Please sign in to comment.