This commit is contained in:
parent
57af33dfed
commit
81aefe3d56
@ -34,6 +34,7 @@ import frc.robot.generated.TunerConstants;
|
||||
//import com.pathplanner.lib.auto.AutoBuilder;
|
||||
//import com.pathplanner.lib.auto.NamedCommands;
|
||||
public class RobotContainer {
|
||||
CommandXboxController manette = new CommandXboxController(0);
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12VoltsMps; // kSpeedAt12VoltsMps desired top speed
|
||||
private double MaxAngularRate = 1.5 * Math.PI; // 3/4 of a rotation per second max angular velocity
|
||||
|
||||
@ -44,19 +45,17 @@ public class RobotContainer {
|
||||
.withDeadband(MaxSpeed * 0.15).withRotationalDeadband(MaxAngularRate * 0.15) // Add a 10% deadband
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // I want field-centric
|
||||
// driving in open loop
|
||||
private final SwerveRequest.SwerveDriveBrake brake = new SwerveRequest.SwerveDriveBrake();
|
||||
private final SwerveRequest.PointWheelsAt point = new SwerveRequest.PointWheelsAt();
|
||||
|
||||
private final Telemetry logger = new Telemetry(MaxSpeed);
|
||||
private void configureBindings() {
|
||||
drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically
|
||||
drivetrain.applyRequest(() -> drive.withVelocityX(-manette.getLeftY() * MaxSpeed*0.25) // Drive forward with
|
||||
drivetrain.applyRequest(() -> drive.withVelocityX(-manette.getLeftY() * MaxSpeed) // Drive forward with
|
||||
// negative Y (forward)
|
||||
.withVelocityY(-manette.getLeftX() * MaxSpeed*0.25) // Drive left with negative X (left)
|
||||
.withRotationalRate(-manette.getRightX() * MaxAngularRate*0.25) // Drive counterclockwise with negative X (left)
|
||||
.withVelocityY(-manette.getLeftX() * MaxSpeed) // Drive left with negative X (left)
|
||||
.withRotationalRate(-manette.getRightX() * MaxAngularRate) // Drive counterclockwise with negative X (left)
|
||||
));
|
||||
|
||||
manette.a().whileTrue(drivetrain.applyRequest(() -> brake));
|
||||
manette.b().whileTrue(drivetrain
|
||||
.applyRequest(() -> point.withModuleDirection(new Rotation2d(-manette.getLeftY(), -manette.getLeftX()))));
|
||||
|
||||
@ -76,7 +75,7 @@ public class RobotContainer {
|
||||
LED led = new LED();
|
||||
//Drive drive = new Drive();
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
CommandXboxController manette = new CommandXboxController(0);
|
||||
|
||||
public RobotContainer() {
|
||||
//NamedCommands.registerCommand("lancer", new Lancer(lanceur, accumulateur));
|
||||
//NamedCommands.registerCommand("Desaccumuler", new Desaccumuler(accumulateur));
|
||||
@ -87,18 +86,8 @@ public class RobotContainer {
|
||||
dashboard.addCamera("limelight3", "limelight3","limelight.local:5800")
|
||||
.withSize(3,4)
|
||||
.withPosition(2,0);
|
||||
final double MaxSpeed = TunerConstants.kSpeedAt12VoltsMps; // kSpeedAt12VoltsMps desired top speed
|
||||
final double MaxAngularRate = 1.5 * Math.PI; // 3/4 of a rotation per second max angular velocity
|
||||
|
||||
/* Setting up bindings for necessary control of the swerve drive platform */ // My joystick
|
||||
|
||||
|
||||
//drive.setDefaultCommand(new RunCommand(()->{
|
||||
// drive.drive(-MathUtil.applyDeadband(manette.getRightX(),0.2), MathUtil.applyDeadband(-manette.getRightY(),0.2), MathUtil.applyDeadband(-manette.getRightX(), 0.2));
|
||||
//},drive));
|
||||
// dashboard.add("autochooser",autoChooser)
|
||||
//.withSize(1,1)
|
||||
// .withPosition(8,0);
|
||||
manette.x().whileTrue(new Lancer(lanceur,accumulateur));
|
||||
manette.leftBumper().toggleOnTrue(new FollowAprilTag(limelight3G, lanceur));
|
||||
manette.a().whileTrue(new Desaccumuler(accumulateur));
|
||||
|
Loading…
x
Reference in New Issue
Block a user