Skip to content
This repository has been archived by the owner on Apr 20, 2024. It is now read-only.

Commit

Permalink
Format
Browse files Browse the repository at this point in the history
  • Loading branch information
jordanjcoderman committed Apr 18, 2024
1 parent 8d9e5df commit 276c5cd
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 7 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/intake/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ public void robotPeriodic() {
motor.setVoltage(8);
break;
case SHUFFLE:
motor.setVoltage(0.5);
motor.setVoltage(0.5);
break;
default:
break;
Expand Down
15 changes: 9 additions & 6 deletions src/main/java/frc/robot/vision/VisionSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,13 @@ public class VisionSubsystem extends LifecycleSubsystem {
public static final Pose2d ORIGINAL_BLUE_SPEAKER =
new Pose2d(Units.inchesToMeters(0), Units.inchesToMeters(218.42), Rotation2d.fromDegrees(0));

public static final Pose2d RED_FLOOR_SPOT_SUBWOOFER = new Pose2d(15.5, 7.9, Rotation2d.fromDegrees(180));
public static final Pose2d BLUE_FLOOR_SPOT_SUBWOOFER = new Pose2d(1, 7.9, Rotation2d.fromDegrees(0));
public static final Pose2d RED_FLOOR_SPOT_SUBWOOFER =
new Pose2d(15.5, 7.9, Rotation2d.fromDegrees(180));
public static final Pose2d BLUE_FLOOR_SPOT_SUBWOOFER =
new Pose2d(1, 7.9, Rotation2d.fromDegrees(0));

public static final Pose2d RED_FLOOR_SPOT_AMP_AREA = new Pose2d(9.5, 7, Rotation2d.fromDegrees(180));
public static final Pose2d RED_FLOOR_SPOT_AMP_AREA =
new Pose2d(9.5, 7, Rotation2d.fromDegrees(180));
public static final Pose2d BLUE_FLOOR_SPOT_AMP_AREA = new Pose2d(7, 7, Rotation2d.fromDegrees(0));

private static final Pose2d RED_FLOOR_SHOT_ROBOT_FALLBACK_POSE =
Expand Down Expand Up @@ -262,13 +265,13 @@ public DistanceAngle getDistanceAngleFloorShot() {
fallbackPose = new Pose2d(fallbackPose.getTranslation(), robotPose.getRotation());
var usedRobotPose = getState() == VisionState.OFFLINE ? fallbackPose : robotPose;

var subwooferSpotDistance = distanceToTargetPose(goalPoseSubwoofer, usedRobotPose);
var subwooferSpotDistance = distanceToTargetPose(goalPoseSubwoofer, usedRobotPose);
var usedGoalPose = goalPoseSubwoofer;
var result = subwooferSpotDistance;

if (subwooferSpotDistance.distance() > 14.0) {
result = distanceToTargetPose(goalPoseAmpArea, usedRobotPose);
usedGoalPose = goalPoseAmpArea;
result = distanceToTargetPose(goalPoseAmpArea, usedRobotPose);
usedGoalPose = goalPoseAmpArea;
}

if (RobotConfig.IS_DEVELOPMENT) {
Expand Down

0 comments on commit 276c5cd

Please sign in to comment.