Skip to content

Commit

Permalink
Pull request fixes (robotToCam) and start branchAlign
Browse files Browse the repository at this point in the history
  • Loading branch information
TimB-87 authored and msoucy committed Jan 30, 2025
1 parent bff46b2 commit 62e8fbd
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 4 deletions.
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/maps/Shrimp.java
Original file line number Diff line number Diff line change
Expand Up @@ -109,14 +109,18 @@ SDSSwerveModule.MK4_V2.wheelDiameter, new PIDValues(0.004, 0.00,

@Override
public VisionMap getVisionMap() {
// Cam mounted 9.029 sideways of center, 9.029 in. forward of center, 9.75 in.
// up from center.
// Front left and front right camera locations
// Cam mounted 9.029 in. sideways of center(left), 9.029 in. forward of center,
// 9.75 in. up from center. Mounted 0 degrees around x axis (roll), angled up
// 65.752 degrees, and rotated side-to-side 45 degrees facing left
Transform3d robotToCamFL = new Transform3d(
new Translation3d(Units.inchesToMeters(-9.029), Units.inchesToMeters(9.029),
Units.inchesToMeters(9.75)),
new Rotation3d(0, Units.degreesToRadians(-65.752), Units.degreesToRadians(45)));

// Cam mounted facing __, __ forward of center, __ up from center.
// Cam mounted 9.029 in. sideways of center(right), 9.029 in. forward of center,
// 9.75 in. up from center. Mounted 0 degrees around x axis (roll), angled up
// 64.752 degrees, and rotated side-to-side 45 degrees facing right
Transform3d robotToCamFR = new Transform3d(
new Translation3d(Units.inchesToMeters(9.029), Units.inchesToMeters(9.029),
Units.inchesToMeters(9.75)),
Expand Down
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.FieldConstants.Reef;

public class Drive extends LoggedSubsystem<SwerveDriveData, SwerveDriveMap> {

Expand Down Expand Up @@ -129,12 +130,21 @@ public Command aimAtReefCenter() {
// Pull reef coords from FieldConstants somehow
// Find nearest reef apriltag (do we need a different method of estimation
// rather than global? Might want to just focus on one tag rather than multiple
// behind the robot)
// behind the robot. Reef tags are blue 17-22, red 6-11)
// Use coords and move command to move to either left or right branch
// (translation to get robotToReef and then move)
// Need rotation in here somewhere. Logic from rotateTo command, since ideally
// we move and rotate at the same time

public enum Branch {
leftBranch,
rightBranch
};

public Command alignToReefBranch(Branch leftBranch, Branch rightBranch) {

};

public Command moveInDirection(double xSpeed, double ySpeed, double seconds) {
return run(() -> {
move(xSpeed, ySpeed, 0, false);
Expand Down

0 comments on commit 62e8fbd

Please sign in to comment.