This commit is contained in:
mimigamin
2026-03-21 15:49:44 -06:00
parent 75cab187e2
commit d639b3076d
7 changed files with 234 additions and 13 deletions
@@ -39,6 +39,7 @@ import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc4388.robot.commands.Swerve.StayInPosition;
import frc4388.robot.commands.alignment.AutoAlign;
import frc4388.robot.constants.Constants;
import frc4388.robot.constants.FieldConstants;
import frc4388.robot.constants.Constants.OIConstants;
import frc4388.robot.constants.Constants.SimConstants.Mode;
import frc4388.robot.subsystems.intake.Intake;
@@ -155,7 +156,7 @@ public class RobotContainer {
new InstantCommand(()-> m_robotShooter.allowShooting(), m_robotShooter),
new WaitCommand(5),
IntakeRetracted,
new WaitCommand(5),
new WaitCommand(10),
new InstantCommand(() -> m_robotShooter.denyShooting(), m_robotShooter),
new InstantCommand(()->m_robotShooter.spinUpIdle(), m_robotShooter)
);
@@ -185,7 +186,29 @@ public class RobotContainer {
// NamedCommands.registerCommand("Lidar Intake", LidarIntake);
NamedCommands.registerCommand("Intake Extended", IntakeExtended);
NamedCommands.registerCommand("Robot Shoot Driving", RobotShootDriving);
NamedCommands.registerCommand("WaitShooter", new WaitUntilCommand(m_robotShooter::isShooterUpToSpeed));
NamedCommands.registerCommand("AllowShooting", new InstantCommand(() -> m_robotShooter.allowShooting(), m_robotShooter));
NamedCommands.registerCommand("DenyShooting", new InstantCommand(() -> m_robotShooter.denyShooting(), m_robotShooter));
NamedCommands.registerCommand("SpinUpShooting", new InstantCommand(() -> m_robotShooter.spinUpShooting(), m_robotShooter));
NamedCommands.registerCommand("SpinUpIdle", new InstantCommand(() -> m_robotShooter.spinUpIdle(), m_robotShooter));
NamedCommands.registerCommand("BumpOffsetForward", new InstantCommand(() -> {
if (TimesNegativeOne.isRed) {
m_robotSwerveDrive.offsetOdoPosition(FieldConstants.BUMP_OFFSET_RED);
} else {
m_robotSwerveDrive.offsetOdoPosition(FieldConstants.BUMP_OFFSET_BLUE);
}
}));
NamedCommands.registerCommand("BumpOffsetReverse", new InstantCommand(() -> {
if (!TimesNegativeOne.isRed) {
m_robotSwerveDrive.offsetOdoPosition(FieldConstants.BUMP_OFFSET_RED);
} else {
m_robotSwerveDrive.offsetOdoPosition(FieldConstants.BUMP_OFFSET_BLUE);
}
}));
DriverStation.silenceJoystickConnectionWarning(true);
@@ -372,8 +395,11 @@ public class RobotContainer {
private void configureSINGLEBindings() {
//Driver controls
// new JoystickButton(getDeadbandedDriverController(), XboxController.A_BUTTON)
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyro()));
new JoystickButton(getDeadbandedDriverController(), XboxController.A_BUTTON)
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyro()));
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.offsetOdoPosition(FieldConstants.BUMP_OFFSET_RED)));
new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON)
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp()));
@@ -7,12 +7,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2026KPopRobotHunters";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 181;
public static final String GIT_SHA = "3c1b94a2d86a624a9320493a0240ee552491beca";
public static final String GIT_DATE = "2026-03-21 13:04:40 MDT";
public static final int GIT_REVISION = 182;
public static final String GIT_SHA = "75cab187e2225e51259336e5569f15c41f9169d5";
public static final String GIT_DATE = "2026-03-21 13:38:34 MDT";
public static final String GIT_BRANCH = "MiraOrg";
public static final String BUILD_DATE = "2026-03-21 13:30:10 MDT";
public static final long BUILD_UNIX_TIME = 1774121410165L;
public static final String BUILD_DATE = "2026-03-21 15:45:59 MDT";
public static final long BUILD_UNIX_TIME = 1774129559544L;
public static final int DIRTY = 1;
private BuildConstants(){}
@@ -1,18 +1,27 @@
package frc4388.robot.constants;
import java.util.Arrays;
import static edu.wpi.first.units.Units.Meters;
import edu.wpi.first.apriltag.AprilTag;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
public final class FieldConstants {
public static final AprilTagFieldLayout kTagLayout = AprilTagFieldLayout.loadField(AprilTagFields.k2026RebuiltAndymark);
public static final double BUMP_OFFSET = 0.4;
public static final Transform2d BUMP_OFFSET_RED = new Transform2d(
Meters.of(BUMP_OFFSET),
Meters.of(0),
new Rotation2d()
);
public static final Transform2d BUMP_OFFSET_BLUE = new Transform2d(
Meters.of(-BUMP_OFFSET),
Meters.of(0),
new Rotation2d()
);
// Test april tag field layout
// public static final AprilTagFieldLayout kTagLayout = new AprilTagFieldLayout(
// Arrays.asList(new AprilTag[] {
@@ -24,6 +24,7 @@ import com.pathplanner.lib.util.PathPlannerLogging;
import edu.wpi.first.math.controller.PIDController;
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.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.units.measure.AngularVelocity;
@@ -433,6 +434,19 @@ public class SwerveDrive extends SubsystemBase implements Queryable {
driveFieldAngle(leftStick, ang);
}
public void offsetOdoPosition(Transform2d offset) {
// Manually performing an addittion on the pose
// WHY doesn't WPILIB have the ability to not transform poses
Pose2d new_pose = new Pose2d(
new Translation2d(
state.currentPose.getX() + offset.getX(),
state.currentPose.getY() + offset.getY()
),
state.currentPose.getRotation()
);
this.io.resetPose(new_pose);
}
public void defenseXPosition(){
io.setControl(new SwerveRequest.SwerveDriveBrake());
}