5
5
package frc .robot ;
6
6
7
7
import com .pathplanner .lib .auto .NamedCommands ;
8
+ import edu .wpi .first .math .controller .ProfiledPIDController ;
8
9
import edu .wpi .first .math .geometry .Pose2d ;
9
10
import edu .wpi .first .math .geometry .Rotation2d ;
10
11
import edu .wpi .first .math .geometry .Translation2d ;
12
+ import edu .wpi .first .math .trajectory .TrapezoidProfile .Constraints ;
11
13
import edu .wpi .first .wpilibj .DriverStation ;
12
14
import edu .wpi .first .wpilibj .Filesystem ;
13
15
import edu .wpi .first .wpilibj .RobotBase ;
@@ -104,7 +106,6 @@ public RobotContainer()
104
106
*/
105
107
private void configureBindings ()
106
108
{
107
-
108
109
Command driveFieldOrientedDirectAngle = drivebase .driveFieldOriented (driveDirectAngle );
109
110
Command driveFieldOrientedAnglularVelocity = drivebase .driveFieldOriented (driveAngularVelocity );
110
111
Command driveRobotOrientedAngularVelocity = drivebase .driveFieldOriented (driveRobotOriented );
@@ -125,8 +126,25 @@ private void configureBindings()
125
126
126
127
if (Robot .isSimulation ())
127
128
{
129
+ driveDirectAngleKeyboard .driveToPose (() -> new Pose2d (new Translation2d (9 , 3 ),
130
+ Rotation2d .fromDegrees (90 )),
131
+ new ProfiledPIDController (5 ,
132
+ 0 ,
133
+ 0 ,
134
+ new Constraints (5 ,
135
+ 3 )),
136
+ new ProfiledPIDController (5 ,
137
+ 0 ,
138
+ 0 ,
139
+ new Constraints (
140
+ Math .toRadians (
141
+ 360 ),
142
+ Math .toRadians (
143
+ 90 ))));
128
144
driverXbox .start ().onTrue (Commands .runOnce (() -> drivebase .resetOdometry (new Pose2d (3 , 3 , new Rotation2d ()))));
129
145
driverXbox .button (1 ).whileTrue (drivebase .sysIdDriveMotorCommand ());
146
+ driverXbox .button (2 ).whileTrue (Commands .runEnd (() -> driveDirectAngleKeyboard .driveToPoseEnabled (true ),
147
+ () -> driveDirectAngleKeyboard .driveToPoseEnabled (false )));
130
148
131
149
}
132
150
if (DriverStation .isTest ())
0 commit comments