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

Commit

Permalink
fix errors
Browse files Browse the repository at this point in the history
  • Loading branch information
gvaldez7206 committed Jan 13, 2024
1 parent 633c2f6 commit db81af7
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 15 deletions.
2 changes: 1 addition & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
"editor.defaultFormatter": "redhat.java",
},
"editor.codeActionsOnSave": {
"source.organizeImports": true
"source.organizeImports": "explicit"
},
"editor.formatOnSave": true,
"editor.formatOnPaste": true,
Expand Down
19 changes: 8 additions & 11 deletions src/main/java/frc/lib/util/PhotonCameraWrapper.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.lib.util;

import java.io.IOException;
import java.util.Optional;
import org.photonvision.EstimatedRobotPose;
import org.photonvision.PhotonCamera;
Expand All @@ -10,7 +9,6 @@
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

Expand All @@ -31,15 +29,14 @@ public PhotonCameraWrapper(String cameraName, Transform3d robotToCam) {
// Change the name of your camera here to whatever it is in the PhotonVision UI.
photonCamera = new PhotonCamera(cameraName);


// Attempt to load the AprilTagFieldLayout that will tell us where the tags are on the
// field.
AprilTagFieldLayout fieldLayout =
AprilTagFields.k2023ChargedUp.loadAprilTagLayoutField();
// Create pose estimator
photonPoseEstimator = new PhotonPoseEstimator(fieldLayout, PoseStrategy.MULTI_TAG_PNP_ON_RIO,
photonCamera, robotToCam);
photonPoseEstimator.setMultiTagFallbackStrategy(PoseStrategy.CLOSEST_TO_CAMERA_HEIGHT);

// Attempt to load the AprilTagFieldLayout that will tell us where the tags are on the
// field.
AprilTagFieldLayout fieldLayout = AprilTagFields.k2023ChargedUp.loadAprilTagLayoutField();
// Create pose estimator
photonPoseEstimator = new PhotonPoseEstimator(fieldLayout,
PoseStrategy.MULTI_TAG_PNP_ON_RIO, photonCamera, robotToCam);
photonPoseEstimator.setMultiTagFallbackStrategy(PoseStrategy.CLOSEST_TO_CAMERA_HEIGHT);
}

/**
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,8 @@ public static final class Swerve {
public static final double TRACK_WIDTH = Units.inchesToMeters(22);
// Left-Right Distance
public static final double WHEEL_BASE = Units.inchesToMeters(22);
public static final double ROBOT_RADIUS = Math.sqrt(Math.pow(TRACK_WIDTH/2,2) + Math.pow(WHEEL_BASE/2,2));
public static final double ROBOT_RADIUS =
Math.sqrt(Math.pow(TRACK_WIDTH / 2, 2) + Math.pow(WHEEL_BASE / 2, 2));
public static final double WHEEL_DIAMETER = Units.inchesToMeters(4);
public static final double WHEEL_CIRCUMFERENCE = WHEEL_DIAMETER * Math.PI;

Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/commands/drive/ClimbPlatform.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,14 @@ public class ClimbPlatform extends Command {
private double startTime;
private int endCount = 0;

private PIDController pidController = new PIDController(-.006, 0, 0);
private PIDController pidController = new PIDController(0, 0, 0);

/**
* Test April tag transform
*/
public ClimbPlatform(Swerve swerve) {
this.swerve = swerve;
pidController.setP(-.006);
this.addRequirements(swerve);
}

Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -143,9 +143,10 @@ public Pose2d getPose() {
return swerveOdometry.getEstimatedPosition();
}

public ChassisSpeeds getChassisSpeeds(){
public ChassisSpeeds getChassisSpeeds() {
return chassisSpeeds;
}

/**
* Resets the robot's position on the field.
*
Expand Down

0 comments on commit db81af7

Please sign in to comment.