Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Minor fixes #123

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 23 additions & 22 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -126,42 +126,43 @@ public RobotContainer(RobotRunType runtimeType) {
for (int i = 0; i < 7; i++) {
numNoteChooser.addOption(String.valueOf(i), i);
}
cameras =
/*
* Camera Order: 0 - Front Left 1 - Front RIght 2 - Back Left 3 - Back Right
*/
new PhotonCameraWrapper[] {
new PhotonCameraWrapper(
new PhotonReal(Constants.CameraConstants.FrontLeftFacingCamera.CAMERA_NAME,
Constants.CameraConstants.FrontLeftFacingCamera.CAMERA_IP),
Constants.CameraConstants.FrontLeftFacingCamera.KCAMERA_TO_ROBOT),
new PhotonCameraWrapper(
new PhotonReal(Constants.CameraConstants.FrontRightFacingCamera.CAMERA_NAME,
Constants.CameraConstants.FrontRightFacingCamera.CAMERA_IP),
Constants.CameraConstants.FrontRightFacingCamera.KCAMERA_TO_ROBOT),
new PhotonCameraWrapper(
new PhotonReal(Constants.CameraConstants.BackLeftFacingCamera.CAMERA_NAME,
Constants.CameraConstants.BackLeftFacingCamera.CAMERA_IP),
Constants.CameraConstants.BackLeftFacingCamera.KCAMERA_TO_ROBOT)};
// new PhotonCameraWrapper(
// new PhotonReal(Constants.CameraConstants.BackRightFacingCamera.CAMERA_NAME),
// Constants.CameraConstants.BackRightFacingCamera.KCAMERA_TO_ROBOT)};

switch (runtimeType) {
case kReal:
cameras =
/*
* Camera Order: 0 - Front Left 1 - Front RIght 2 - Back Left 3 - Back Right
*/
new PhotonCameraWrapper[] {new PhotonCameraWrapper(
new PhotonReal(Constants.CameraConstants.FrontLeftFacingCamera.CAMERA_NAME,
Constants.CameraConstants.FrontLeftFacingCamera.CAMERA_IP),
Constants.CameraConstants.FrontLeftFacingCamera.KCAMERA_TO_ROBOT),
new PhotonCameraWrapper(
new PhotonReal(
Constants.CameraConstants.FrontRightFacingCamera.CAMERA_NAME,
Constants.CameraConstants.FrontRightFacingCamera.CAMERA_IP),
Constants.CameraConstants.FrontRightFacingCamera.KCAMERA_TO_ROBOT),
new PhotonCameraWrapper(
new PhotonReal(
Constants.CameraConstants.BackLeftFacingCamera.CAMERA_NAME,
Constants.CameraConstants.BackLeftFacingCamera.CAMERA_IP),
Constants.CameraConstants.BackLeftFacingCamera.KCAMERA_TO_ROBOT)};
// new PhotonCameraWrapper(
// new PhotonReal(Constants.CameraConstants.BackRightFacingCamera.CAMERA_NAME),
// Constants.CameraConstants.BackRightFacingCamera.KCAMERA_TO_ROBOT)};
shooter = new Shooter(new ShooterVortex());
intake = new Intake(new IntakeIOFalcon());
s_Swerve = new Swerve(new SwerveReal(), cameras);
elevatorWrist = new ElevatorWrist(new ElevatorWristReal(), operator);
break;
case kSimulation:
s_Swerve = new Swerve(new SwerveIO() {}, cameras);
s_Swerve = new Swerve(new SwerveIO() {}, new PhotonCameraWrapper[] {});
shooter = new Shooter(new ShooterIO() {});
intake = new Intake(new IntakeIO() {});
elevatorWrist = new ElevatorWrist(new ElevatorWristIO() {}, operator);
break;
default:
s_Swerve = new Swerve(new SwerveIO() {}, cameras);
s_Swerve = new Swerve(new SwerveIO() {}, new PhotonCameraWrapper[] {});
shooter = new Shooter(new ShooterIO() {});
intake = new Intake(new IntakeIO() {});
elevatorWrist = new ElevatorWrist(new ElevatorWristIO() {}, operator);
Expand Down
9 changes: 4 additions & 5 deletions src/main/java/frc/robot/autos/P8765.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,10 @@
import java.util.function.BooleanSupplier;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.path.PathPlannerTrajectory.State;
import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
Expand Down Expand Up @@ -124,10 +124,9 @@ public P8765(Swerve swerveDrive, ElevatorWrist elevatorWrist, Intake intake, Sho

Command wait = Commands.waitSeconds(.01);
Command resetPosition = Commands.runOnce(() -> {
Pose2d initialState =
FieldConstants.allianceFlip(path0.getPreviewStartingHolonomicPose()
.plus(new Transform2d(0, 0, Rotation2d.fromDegrees(180))));
swerveDrive.resetOdometry(initialState);
State initalState = path0.getTrajectory(null, null).getInitialState();
Pose2d initialPose = FieldConstants.allianceFlip(initalState.getTargetHolonomicPose());
Comment on lines +127 to +128
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should work to allow us to not have to hardcode the 180 degrees. This exposes the actual value from Coreo.... If I remember properly

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks like that'd be the case. Should run it in the shop on Monday to be sure.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My thought exactly

swerveDrive.resetOdometry(initialPose);
});

Command followPaths = part0.andThen(Commands.either(
Expand Down
Loading