// 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.wpilibj.GenericHID; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.robot.subsystems.Drivetrain; public class RobotContainer { private final Drivetrain m_drive = new Drivetrain(); private final GenericHID 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.arcade( // deadzone(-1, 1, m_controller.getRawAxis(1) * Constants.DriveMaxSpeed), // deadzone(-1, 1, m_controller.getRawAxis(0) * Constants.DriveMaxAngular) // ))); m_drive.tank( deadzone(-0.09, 0.09, m_controller.getRawAxis(1)) * Constants.DriveMaxSpeed, deadzone(-0.09, 0.09, m_controller.getRawAxis(3)) * Constants.DriveMaxSpeed ))); new Trigger(() -> m_controller.getRawButton(1)).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()); })); new Trigger(() -> m_controller.getRawButton(2)).onTrue(Commands.runOnce(() -> { System.out.println("Reset"); m_drive.reset(); })); // new Trigger(() -> m_controller.getRawButton(3)).onTrue(Commands.run(() -> { // m_drive.tank(5, 5); // })); } public Command getAutonomousCommand() { return Commands.print("No autonomous command configured"); } }