Skip to content

Commit

Permalink
slower mode
Browse files Browse the repository at this point in the history
Co-authored-by: Andy Killorin <[email protected]>
  • Loading branch information
Sha-dos and Speedy6451 committed Nov 17, 2023
1 parent 8770574 commit fc3cb15
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 5 deletions.
2 changes: 1 addition & 1 deletion src/main/java/com/team2502/robot2023/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ public static final class Leds {
public static final class Arm {
public static final boolean NT_TUNE = false;

public static final double ELEVATOR_LIM_TOP = 85;
public static final double ELEVATOR_LIM_TOP = 90;
public static final double ELEVATOR_LIM_BOTTOM = 0;

public static final double ELEVATOR_P = 0.5;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/com/team2502/robot2023/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public class RobotContainer {

protected final LightstripSubsystem LIGHTSTRIP = new LightstripSubsystem();

protected final PhotonVisionSubsystem VISION = new PhotonVisionSubsystem(DRIVETRAIN);
//protected final PhotonVisionSubsystem VISION = new PhotonVisionSubsystem(DRIVETRAIN);

public RobotContainer() {
DRIVETRAIN.setDefaultCommand(new DriveCommand(DRIVETRAIN, JOYSTICK_DRIVE_LEFT, JOYSTICK_DRIVE_RIGHT));
Expand Down
16 changes: 13 additions & 3 deletions src/main/java/com/team2502/robot2023/commands/DriveCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj2.command.InstantCommand;

public class DriveCommand extends CommandBase {
private final DrivetrainSubsystem drivetrain;
Expand Down Expand Up @@ -46,6 +47,8 @@ private enum Drivetype {
private boolean slowmode = false;
private boolean prevTog = false;

private boolean slower = false;

private final SendableChooser<Drivetype> typeEntry = new SendableChooser<>();
private final SendableChooser<DriveController> controllerEntry = new SendableChooser<>();

Expand All @@ -70,6 +73,8 @@ public DriveCommand(DrivetrainSubsystem drivetrain, Joystick joystickDriveLeft,
controllerEntry.addOption("Xbox", DriveController.Xbox);
SmartDashboard.putData("Drive Controller", controllerEntry);

SmartDashboard.putBoolean("slower", slower);

addRequirements(drivetrain);
}

Expand All @@ -86,6 +91,7 @@ public void execute() {
prevTog = tog;

SmartDashboard.putBoolean("iosajioj", slowmode);
slower = SmartDashboard.getBoolean("slower", false);

ChassisSpeeds speeds;
Translation2d centerOfRotation;
Expand Down Expand Up @@ -140,9 +146,13 @@ public void execute() {
break;
case FieldOrientedTwistRetDead:
speeds = ChassisSpeeds.fromFieldRelativeSpeeds(
Utils.deadzone(Drivetrain.OI_DEADZONE_XY, 0.04, leftJoystick.getY(), 0.45 * 0.6) * (slowmode ? Drivetrain.RET_VEL : Drivetrain.MAX_VEL),
-Utils.deadzone(Drivetrain.OI_DEADZONE_XY, 0.04, leftJoystick.getX(), 0.45 * 0.6) * (slowmode ? Drivetrain.RET_VEL : Drivetrain.MAX_VEL),
-Utils.deadzone(Drivetrain.OI_DEADZONE_Z, 0.04, rightJoystick.getZ(), 0.55 * 0.6) * (slowmode ? Drivetrain.RET_ROT : Drivetrain.MAX_ROT),
Utils.deadzone(Drivetrain.OI_DEADZONE_XY, 0.04, leftJoystick.getY(), 0.45 * (slowmode ? Drivetrain.RET_VEL : Drivetrain.MAX_VEL))
* (slower ? 0.12 : 1),
-Utils.deadzone(Drivetrain.OI_DEADZONE_XY, 0.04, leftJoystick.getX(), 0.45 * (slowmode ? Drivetrain.RET_VEL : Drivetrain.MAX_VEL))
* (slower ? 0.12 : 1),
-Utils.deadzone(Drivetrain.OI_DEADZONE_Z, 0.04, rightJoystick.getZ(), 0.55)
* (slower ? 0.35 : 1)
* (slowmode ? Drivetrain.RET_ROT : Drivetrain.MAX_ROT),
Rotation2d.fromDegrees(drivetrain.getHeading()+drivetrain.fieldOrientedOffset));
centerOfRotation = new Translation2d(0, 0);
drivetrain.setSpeeds(speeds, centerOfRotation);
Expand Down

0 comments on commit fc3cb15

Please sign in to comment.