55package frc .robot ;
66
77import com .pathplanner .lib .auto .NamedCommands ;
8- import edu .wpi .first .math .MathUtil ;
98import edu .wpi .first .math .geometry .Pose2d ;
109import edu .wpi .first .math .geometry .Rotation2d ;
1110import edu .wpi .first .math .geometry .Translation2d ;
1716import edu .wpi .first .wpilibj2 .command .button .CommandXboxController ;
1817import edu .wpi .first .wpilibj2 .command .button .Trigger ;
1918import frc .robot .Constants .OperatorConstants ;
20- import frc .robot .commands .swervedrive .drivebase .AbsoluteDriveAdv ;
2119import frc .robot .subsystems .swervedrive .SwerveSubsystem ;
2220import java .io .File ;
2321import swervelib .SwerveInputStream ;
@@ -35,24 +33,6 @@ public class RobotContainer
3533 // The robot's subsystems and commands are defined here...
3634 private final SwerveSubsystem drivebase = new SwerveSubsystem (new File (Filesystem .getDeployDirectory (),
3735 "swerve/neo" ));
38- // Applies deadbands and inverts controls because joysticks
39- // are back-right positive while robot
40- // controls are front-left positive
41- // left stick controls translation
42- // right stick controls the rotational velocity
43- // buttons are quick rotation positions to different ways to face
44- // WARNING: default buttons are on the same buttons as the ones defined in configureBindings
45- AbsoluteDriveAdv closedAbsoluteDriveAdv = new AbsoluteDriveAdv (drivebase ,
46- () -> -MathUtil .applyDeadband (driverXbox .getLeftY (),
47- OperatorConstants .LEFT_Y_DEADBAND ),
48- () -> -MathUtil .applyDeadband (driverXbox .getLeftX (),
49- OperatorConstants .DEADBAND ),
50- () -> -MathUtil .applyDeadband (driverXbox .getRightX (),
51- OperatorConstants .RIGHT_X_DEADBAND ),
52- driverXbox .getHID ()::getYButtonPressed ,
53- driverXbox .getHID ()::getAButtonPressed ,
54- driverXbox .getHID ()::getXButtonPressed ,
55- driverXbox .getHID ()::getBButtonPressed );
5636
5737 /**
5838 * Converts driver input into a field-relative ChassisSpeeds that is controlled by angular velocity.
@@ -73,22 +53,6 @@ public class RobotContainer
7353 .headingWhile (true );
7454
7555
76- // Applies deadbands and inverts controls because joysticks
77- // are back-right positive while robot
78- // controls are front-left positive
79- // left stick controls translation
80- // right stick controls the desired angle NOT angular rotation
81- Command driveFieldOrientedDirectAngle = drivebase .driveFieldOriented (driveDirectAngle );
82-
83- // Applies deadbands and inverts controls because joysticks
84- // are back-right positive while robot
85- // controls are front-left positive
86- // left stick controls translation
87- // right stick controls the angular velocity of the robot
88- Command driveFieldOrientedAnglularVelocity = drivebase .driveFieldOriented (driveAngularVelocity );
89-
90- Command driveSetpointGen = drivebase .driveWithSetpointGeneratorFieldRelative (driveDirectAngle );
91-
9256 SwerveInputStream driveAngularVelocitySim = SwerveInputStream .of (drivebase .getSwerveDrive (),
9357 () -> -driverXbox .getLeftY (),
9458 () -> -driverXbox .getLeftX ())
@@ -107,12 +71,6 @@ public class RobotContainer
10771 (Math .PI * 2 ))
10872 .headingWhile (true );
10973
110- Command driveFieldOrientedDirectAngleSim = drivebase .driveFieldOriented (driveDirectAngleSim );
111-
112- Command driveFieldOrientedAnglularVelocitySim = drivebase .driveFieldOriented (driveAngularVelocitySim );
113-
114- Command driveSetpointGenSim = drivebase .driveWithSetpointGeneratorFieldRelative (driveDirectAngleSim );
115-
11674 /**
11775 * The container for the robot. Contains subsystems, OI devices, and commands.
11876 */
@@ -133,10 +91,22 @@ public RobotContainer()
13391 */
13492 private void configureBindings ()
13593 {
136- // (Condition) ? Return-On-True : Return-on-False
137- drivebase .setDefaultCommand (!RobotBase .isSimulation () ?
138- driveFieldOrientedAnglularVelocity :
139- driveFieldOrientedAnglularVelocitySim );
94+
95+ Command driveFieldOrientedDirectAngle = drivebase .driveFieldOriented (driveDirectAngle );
96+ Command driveFieldOrientedAnglularVelocity = drivebase .driveFieldOriented (driveAngularVelocity );
97+ Command driveSetpointGen = drivebase .driveWithSetpointGeneratorFieldRelative (driveDirectAngle );
98+ Command driveFieldOrientedDirectAngleSim = drivebase .driveFieldOriented (driveDirectAngleSim );
99+ Command driveFieldOrientedAnglularVelocitySim = drivebase .driveFieldOriented (driveAngularVelocitySim );
100+ Command driveSetpointGenSim = drivebase .driveWithSetpointGeneratorFieldRelative (
101+ driveDirectAngleSim );
102+
103+ if (RobotBase .isSimulation ())
104+ {
105+ drivebase .setDefaultCommand (driveFieldOrientedDirectAngleSim );
106+ } else
107+ {
108+ drivebase .setDefaultCommand (driveFieldOrientedAnglularVelocity );
109+ }
140110
141111 if (Robot .isSimulation ())
142112 {
0 commit comments