Skip to content

Commit

Permalink
Small Changes (#16)
Browse files Browse the repository at this point in the history
* Small Changes

* Created Operator Controller
* Updated WPILib
* Updated AutoBuilder constants

* fix: used operator controller port
  • Loading branch information
ReeledWarrior14 authored Feb 23, 2024
1 parent 8bb305a commit 346f602
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 12 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1"
id "edu.wpi.first.GradleRIO" version "2024.3.1"
}

java {
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,9 @@ public final class Constants {
*/
public static final class IOConstants {
public static final int kDriverControllerPort = 0;
public static final int kOperatorControllerPort = 1;

public static final double kControllerDeadband = 0.2;
public static final double kControllerDeadband = 0.05;
public static final double kSlowModeScalar = 0.8;
}

Expand Down
20 changes: 10 additions & 10 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,10 @@ public class RobotContainer {
private final ShooterSubsystem m_shooterSubsystem = new ShooterSubsystem();

private final XboxController m_driverController = new XboxController(IOConstants.kDriverControllerPort);
private final XboxController m_operatorController = new XboxController(IOConstants.kOperatorControllerPort);

/**
* The container for the robot. Contains subsystems, OI devices, and commands.
* The container for the robot. Contains subsystems, IO devices, and commands.
*/
public RobotContainer() {

Expand All @@ -50,8 +51,8 @@ public RobotContainer() {
new HolonomicPathFollowerConfig(
new PIDConstants(5, 0.0, 0.0), // Translation PID constants
new PIDConstants(5, 0.0, 0.0), // Rotation PID constants
4.5, // Max module speed, in m/s
0.4, // Drive base radius in meters. Distance from robot center to furthest module.
DriveConstants.kMaxSpeedMetersPerSecond, // Max module speed, in m/s
Math.hypot(DriveConstants.kTrackWidth, DriveConstants.kWheelBase), // Drive base radius in meters. Distance from robot center to furthest module.
new ReplanningConfig(true, true)),
() -> false, m_robotDrive);

Expand All @@ -67,16 +68,16 @@ public RobotContainer() {
* DriveConstants.kMaxSpeedMetersPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
* IOConstants.kSlowModeScalar)
* 0.8,
* IOConstants.kSlowModeScalar),
// * 0.8,
MathUtil.applyDeadband(
-m_driverController.getLeftX(),
IOConstants.kControllerDeadband)
* DriveConstants.kMaxSpeedMetersPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
* IOConstants.kSlowModeScalar)
* 0.8,
* IOConstants.kSlowModeScalar),
// * 0.8,
MathUtil.applyDeadband(
-m_driverController.getRightX(),
IOConstants.kControllerDeadband)
Expand All @@ -100,11 +101,10 @@ private void configureBindings() {
// AutoBuilder.pathfindToPose(new Pose2d(2.8, 5.5, new Rotation2d()), new PathConstraints(
// DriveConstants.kMaxSpeedMetersPerSecond - 1, 5, DriveConstants.kMaxAngularSpeedRadiansPerSecond - 1, 5)));

// TODO: Move shoot commands to operator controller
new JoystickButton(m_driverController, Button.kX.value)
new JoystickButton(m_operatorController, Button.kX.value)
.onTrue(new InstantCommand(() -> m_shooterSubsystem.spin(0.75), m_shooterSubsystem))
.onFalse(new InstantCommand(() -> m_shooterSubsystem.spin(0), m_shooterSubsystem));
new JoystickButton(m_driverController, Button.kY.value)
new JoystickButton(m_operatorController, Button.kY.value)
.onTrue(new InstantCommand(() -> m_shooterSubsystem.spin(-0.75), m_shooterSubsystem))
.onFalse(new InstantCommand(() -> m_shooterSubsystem.spin(0), m_shooterSubsystem));
}
Expand Down

0 comments on commit 346f602

Please sign in to comment.