Skip to content
Merged
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
4 changes: 2 additions & 2 deletions src/main/java/raidzero/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ public class Joint {
public static final int CANCODER_ID = 11;

public static final double CANCODER_GEAR_RATIO = 28.0 / 80.0;
public static final double CANCODER_OFFSET = -(0.358643 - (0.25 / CANCODER_GEAR_RATIO));
public static final double CANCODER_OFFSET = -(0.358398 - (0.25 / CANCODER_GEAR_RATIO));
public static final double CANCODER_DISCONTINUITY_POINT = 0.5;

public static final double CONVERSION_FACTOR = (120.0 / 12.0) * 20.0;
Expand All @@ -196,7 +196,7 @@ public class Joint {

public class Positions {
public static final double[] L4_SCORING_POS_M = { -0.24, 2.72 };
public static final double[] L4_SCORING_POS_M_BLUE = { -0.15, 2.72 };
public static final double[] L4_SCORING_POS_M_BLUE = { -0.17, 2.68 };
public static final double[] L4_CHECK_POSITION = { -0.25, 2.62 };
public static final double[] L4_GRAND_SLAM = { -0.2, 1.57 };

Expand Down
12 changes: 8 additions & 4 deletions src/main/java/raidzero/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,9 @@ public RobotContainer() {
private void configureBindings() {
swerve.setDefaultCommand(
swerve.applyRequest(
() -> fieldCentricDrive.withVelocityX(-joystick.getLeftY() * MaxSpeed * 0.67 * (arm.isUp() ? 0.3 : 1.0))
.withVelocityY(-joystick.getLeftX() * MaxSpeed * 0.67 * (arm.isUp() ? 0.3 : 1.0))
() -> fieldCentricDrive
.withVelocityX(-joystick.getLeftY() * MaxSpeed * swerve.getSpeedModifier() * (arm.isUp() ? 0.3 : 1.0))
.withVelocityY(-joystick.getLeftX() * MaxSpeed * swerve.getSpeedModifier() * (arm.isUp() ? 0.3 : 1.0))
.withRotationalRate(-joystick.getRightX() * MaxAngularRate)
)
);
Expand All @@ -108,8 +109,8 @@ private void configureBindings() {
)
);

joystick.leftBumper().whileTrue(coralIntake.extake());
joystick.rightBumper().onTrue(coralIntake.intake());
joystick.leftTrigger().whileTrue(coralIntake.extake());
joystick.rightTrigger().onTrue(coralIntake.intake());

joystick.b().whileTrue(
swerve.pathToStation()
Expand All @@ -133,6 +134,9 @@ private void configureBindings() {
arm.moveWithDelay(Constants.TelescopingArm.Positions.INTAKE_POS_M_BLUE)
);

joystick.rightBumper().onTrue(new InstantCommand(() -> swerve.setSpeedModifier(1.0)));
joystick.leftBumper().onTrue(new InstantCommand(() -> swerve.setSpeedModifier(0.67)));

// * Operator controls
operator.button(Constants.Bindings.TOP_LEFT).onTrue(new InstantCommand(() -> arm.decreaseIntakeYOffset(0.01), arm));
operator.button(Constants.Bindings.BOTTOM_LEFT).onTrue(new InstantCommand(() -> arm.decreaseIntakeYOffset(-0.01), arm));
Expand Down
22 changes: 22 additions & 0 deletions src/main/java/raidzero/robot/subsystems/drivetrain/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ public class Swerve extends TunerSwerveDrivetrain implements Subsystem {

private boolean waypointsTransformed = false;

private double speedModifier = 0.67;

private static Swerve system;

/*
Expand Down Expand Up @@ -389,6 +391,24 @@ public Command stop() {
);
}

/**
* Gets the current modifier for max speed
*
* @return the modifier for max speed
*/
public double getSpeedModifier() {
return speedModifier;
}

/**
* Sets the current modifi9er for max speed
*
* @param speedModifier the modifier for max speed
*/
public void setSpeedModifier(double speedModifier) {
this.speedModifier = speedModifier;
}

@Override
public void periodic() {
/*
Expand Down Expand Up @@ -419,6 +439,8 @@ public void periodic() {
modulePublisher.set(this.getState().ModuleStates);
botpose.set(this.getState().Pose);
field.setRobotPose(this.getState().Pose);

SmartDashboard.putNumber("Bot Speed", speedModifier * 100.0);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -335,8 +335,9 @@ private TalonFXConfiguration telescopeConfiguration() {
.withMotionMagicAcceleration(Constants.TelescopingArm.Telescope.ACCELERATION)
.withMotionMagicJerk(Constants.TelescopingArm.Telescope.JERK);

configuration.HardwareLimitSwitch.ForwardLimitAutosetPositionEnable = true;
configuration.HardwareLimitSwitch.ForwardLimitAutosetPositionValue = 0.0;
configuration.HardwareLimitSwitch.ReverseLimitAutosetPositionEnable = true;
configuration.HardwareLimitSwitch.ReverseLimitAutosetPositionValue = 0.0;
configuration.HardwareLimitSwitch.ReverseLimitEnable = false;

configuration.Feedback.SensorToMechanismRatio = Constants.TelescopingArm.Telescope.CONVERSION_FACTOR;

Expand Down