summaryrefslogtreecommitdiff
path: root/src/main/java/frc/robot/RobotContainer.java
blob: ed6afe92a6b460c8ab947e0be0c8c56b7f045e2f (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
// 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");
    }
}