Skip to content

Commit

Permalink
other chairbot
Browse files Browse the repository at this point in the history
  • Loading branch information
jack60612 committed Jan 8, 2024
1 parent f0090ab commit b177930
Show file tree
Hide file tree
Showing 3 changed files with 69 additions and 1 deletion.
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,11 @@
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.commands.AimCommand;
import frc.robot.commands.BalanceCommand;
import frc.robot.commands.BreakCommand;
import frc.robot.commands.DefaultDrive;
import frc.robot.commands.DriftCommand;
import frc.robot.commands.RawDrive;
import frc.robot.commands.StraightRawCommand;
import frc.robot.subsystems.DriveSubsystem;
import frc.robot.subsystems.UltrasonicSubsystem;
import java.util.HashMap;
Expand Down Expand Up @@ -59,10 +61,16 @@ public class RobotContainer {
// misc init
private final DriftCommand m_driftCommand =
new DriftCommand(m_driveSubsystem, this::getControllerLeftY, this::getControllerRightY);
private final StraightRawCommand m_straightRawCommand =
new StraightRawCommand(m_driveSubsystem, this::getControllerLeftY, this::getControllerRightY);
private final BreakCommand m_breakCommand =
new BreakCommand(m_driveSubsystem, this::getControllerLeftY, this::getControllerRightY);
private Trigger m_switchCameraButton;
private Trigger m_balanceButton;
private Trigger m_rawDriveButton;
private Trigger m_driftButton;
private Trigger m_straightRawButton;
private Trigger m_breakButton;
private JoystickButton m_aimButton;
// Init For Autonomous
private RamseteAutoBuilder autoBuilder;
Expand Down Expand Up @@ -93,13 +101,17 @@ private void configureButtonBindings() {
m_balanceButton = m_controller1.rightBumper();
m_rawDriveButton = m_controller1.rightTrigger();
m_driftButton = m_controller1.leftTrigger();
m_straightRawButton = m_controller1.rightBumper();
m_breakButton = m_controller1.leftBumper();
// Joystick buttons
m_aimButton = new JoystickButton(m_flightStick, Constants.AIMBUTTON);
// commands
m_balanceButton.whileTrue(m_balanceCommand);
m_rawDriveButton.whileTrue(m_RawDriveCommand);
m_aimButton.whileTrue(m_aimCommand);
m_driftButton.whileTrue(m_driftCommand);
m_straightRawButton.whileTrue(m_straightRawCommand);
m_breakButton.whileTrue(m_breakCommand);

m_controller1.a().whileTrue(new InstantCommand(() -> m_driveSubsystem.SetBrakemode()));
m_controller1.b().whileTrue(new InstantCommand(() -> m_driveSubsystem.SetCoastmode()));
Expand Down
57 changes: 57 additions & 0 deletions src/main/java/frc/robot/commands/BreakCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
// 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.commands;

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.DriveSubsystem;
import java.util.function.DoubleSupplier;

/** An example command that uses an example subsystem. */
public class BreakCommand extends CommandBase {
private final DriveSubsystem m_driveSubsystem;
private final DoubleSupplier m_left_y; // this gives us the left y axis for current controller
private final DoubleSupplier m_right_y; // this gives us the right y axis for current controller
/**
* Creates a new StraightCommand.
*
* @param d_subsystem The drive subsystem used by this command.
* @param xbox_left_y A function that returns the value of the left y axis for the joystick.
* @param xbox_right_y A function that returns the value of the right Y axis for the joystick.
*/
public BreakCommand(
DriveSubsystem d_subsystem, DoubleSupplier xbox_left_y, DoubleSupplier xbox_right_y) {
m_driveSubsystem = d_subsystem;
m_left_y = xbox_left_y;
m_right_y = xbox_right_y;

// Change this to match the name of your camera
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(d_subsystem);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
System.out.println("Starting 'StraightCommand.");
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_driveSubsystem.tankDrive(0.7, 0.7);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_driveSubsystem.turnResetPID(); // we make sure to clear the PID angle
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
1 change: 0 additions & 1 deletion src/main/java/frc/robot/commands/DriftCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ public void initialize() {
@Override
public void execute() {
m_driveSubsystem.tankDrive(m_left_y.getAsDouble(), m_right_y.getAsDouble());
;
}

// Called once the command ends or is interrupted.
Expand Down

0 comments on commit b177930

Please sign in to comment.