Skip to content

Commit

Permalink
some tunings during test
Browse files Browse the repository at this point in the history
  • Loading branch information
catr1xLiu committed Dec 4, 2024
1 parent 9c1e10c commit 40f5076
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 5 deletions.
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
import org.ironmaple.simulation.drivesims.SwerveDriveSimulation;
import org.ironmaple.simulation.drivesims.SwerveModuleSimulation;
import org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig;
import org.ironmaple.utils.FieldMirroringUtils;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

Expand Down Expand Up @@ -296,7 +297,9 @@ public void configureButtonBindings() {
driverXBox
.start()
.onTrue(Commands.runOnce(
() -> drive.setPose(new Pose2d(drive.getPose().getTranslation(), new Rotation2d())),
() -> drive.setPose(new Pose2d(
drive.getPose().getTranslation(),
FieldMirroringUtils.getCurrentAllianceDriverStationFacing())),
drive)
.ignoringDisable(true));

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ public class TunerConstants {
public static final int kFrontRightDriveMotorId = 3;
public static final int kFrontRightSteerMotorId = 4;
public static final int kFrontRightEncoderId = 2;
public static final Angle kFrontRightEncoderOffset = Rotations.of(-0.230712890625);
public static final Angle kFrontRightEncoderOffset = Rotations.of(-0.730712890625);
public static final boolean kFrontRightSteerMotorInverted = true;
public static final boolean kFrontRightCANcoderInverted = false;

Expand All @@ -169,7 +169,7 @@ public class TunerConstants {
public static final int kBackRightDriveMotorId = 7;
public static final int kBackRightSteerMotorId = 8;
public static final int kBackRightEncoderId = 4;
public static final Angle kBackRightEncoderOffset = Rotations.of(-0.05419921875);
public static final Angle kBackRightEncoderOffset = Rotations.of(-0.55419921875);
public static final boolean kBackRightSteerMotorInverted = true;
public static final boolean kBackRightCANcoderInverted = false;

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/VisionConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ public class VisionConstants {
public static final AprilTagFieldLayout fieldLayout = AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
public static final double
/* default standard error for vision observation, if only one apriltag observed */
TRANSLATIONAL_STANDARD_ERROR_METERS_FOR_SINGLE_OBSERVATION = 2,
ROTATIONAL_STANDARD_ERROR_RADIANS_FOR_SINGLE_OBSERVATION = Math.toRadians(30),
TRANSLATIONAL_STANDARD_ERROR_METERS_FOR_SINGLE_OBSERVATION = 4,
ROTATIONAL_STANDARD_ERROR_RADIANS_FOR_SINGLE_OBSERVATION = Math.toRadians(60),
TRANSLATIONAL_STANDARD_ERROR_METERS_FOR_MULTITAG = 0.5,
ROTATIONAL_STANDARD_ERROR_RADIANS_FOR_MULTITAG = Math.toRadians(8),

Expand Down

0 comments on commit 40f5076

Please sign in to comment.