// Copyright (c) FIRST and other WPILib contributors. // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. package frc.robot; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.subsystems.Drivetrain; public class RobotContainer { private final Drivetrain m_drive = new Drivetrain(); private final CommandXboxController m_controller = Constants.controller; public RobotContainer() { configureBindings(); } private double deadzone(double low, double high, double val) { if(val > low && val < high) return 0.0; return val; } private void configureBindings() { m_drive.setDefaultCommand(m_drive.run(() -> m_drive.tank( deadzone(-0.09, 0.09, m_controller.getLeftY()) * Constants.DriveMaxSpeed, deadzone(-0.09, 0.09, m_controller.getRightY()) * Constants.DriveMaxSpeed ))); // debug controls m_controller.a().onTrue(Commands.runOnce(() -> { Pose2d pose = m_drive.pose2d(); System.out.println("x: " + pose.getX() +" y: "+ pose.getY()); System.out.println("yaw: " + Constants.gyro.toRotation2d().getDegrees()); })); m_controller.b().onTrue(Commands.runOnce(() -> { System.out.println("Reset"); m_drive.reset(); })); m_controller.x().and(m_controller.leftBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Quasistatic Forward")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kForward))); m_controller.x().and(m_controller.rightBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Quasistatic Reverse")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kReverse))); m_controller.y().and(m_controller.leftBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Dynamic Forward")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kForward))); m_controller.y().and(m_controller.rightBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Dynamic Reverse")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kReverse))); } public Command getAutonomousCommand() { return Commands.print("No autonomous command configured"); } }