5
5
package frc .robot ;
6
6
7
7
import com .pathplanner .lib .auto .NamedCommands ;
8
- import edu .wpi .first .math .MathUtil ;
9
8
import edu .wpi .first .math .geometry .Pose2d ;
10
9
import edu .wpi .first .math .geometry .Rotation2d ;
11
10
import edu .wpi .first .math .geometry .Translation2d ;
17
16
import edu .wpi .first .wpilibj2 .command .button .CommandXboxController ;
18
17
import edu .wpi .first .wpilibj2 .command .button .Trigger ;
19
18
import frc .robot .Constants .OperatorConstants ;
20
- import frc .robot .commands .swervedrive .drivebase .AbsoluteDriveAdv ;
21
19
import frc .robot .subsystems .swervedrive .SwerveSubsystem ;
22
20
import java .io .File ;
23
21
import swervelib .SwerveInputStream ;
@@ -35,24 +33,6 @@ public class RobotContainer
35
33
// The robot's subsystems and commands are defined here...
36
34
private final SwerveSubsystem drivebase = new SwerveSubsystem (new File (Filesystem .getDeployDirectory (),
37
35
"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 );
56
36
57
37
/**
58
38
* Converts driver input into a field-relative ChassisSpeeds that is controlled by angular velocity.
@@ -73,22 +53,6 @@ public class RobotContainer
73
53
.headingWhile (true );
74
54
75
55
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
-
92
56
SwerveInputStream driveAngularVelocitySim = SwerveInputStream .of (drivebase .getSwerveDrive (),
93
57
() -> -driverXbox .getLeftY (),
94
58
() -> -driverXbox .getLeftX ())
@@ -107,12 +71,6 @@ public class RobotContainer
107
71
(Math .PI * 2 ))
108
72
.headingWhile (true );
109
73
110
- Command driveFieldOrientedDirectAngleSim = drivebase .driveFieldOriented (driveDirectAngleSim );
111
-
112
- Command driveFieldOrientedAnglularVelocitySim = drivebase .driveFieldOriented (driveAngularVelocitySim );
113
-
114
- Command driveSetpointGenSim = drivebase .driveWithSetpointGeneratorFieldRelative (driveDirectAngleSim );
115
-
116
74
/**
117
75
* The container for the robot. Contains subsystems, OI devices, and commands.
118
76
*/
@@ -133,10 +91,22 @@ public RobotContainer()
133
91
*/
134
92
private void configureBindings ()
135
93
{
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
+ }
140
110
141
111
if (Robot .isSimulation ())
142
112
{
0 commit comments