From 83ea560d2ec79a36e68f33130496e7c9e8896548 Mon Sep 17 00:00:00 2001 From: SorinEngUS Date: Tue, 28 Nov 2023 17:12:37 -0800 Subject: [PATCH] made button --- src/main/java/frc/robot/RobotContainer.java | 6 ++++++ src/main/java/frc/robot/Subsystems/ElevatorSubsystem.java | 2 ++ 2 files changed, 8 insertions(+) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index c09eaf6..3a49c49 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -6,8 +6,10 @@ import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import frc.robot.Commands.ElevatorCommand; import frc.robot.Commands.IntakeCommand; import frc.robot.Commands.StopIntakeMotorCommand; +import frc.robot.Subsystems.ElevatorSubsystem; import frc.robot.Subsystems.IntakeSubsystem; /** @@ -24,6 +26,7 @@ public class RobotContainer { private final IntakeSubsystem intakeSubsystem = new IntakeSubsystem(); + private final ElevatorSubsystem elevatorSubsystem = new ElevatorSubsystem(); /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { // Configure the button bindings @@ -70,5 +73,8 @@ private void configureButtonBindings() { // stop the motors driverB.x().onTrue(new StopIntakeMotorCommand(intakeSubsystem)); + + driverB.y().onTrue(new ElevatorCommand(elevatorSubsystem, 10)); + driverB.b().onTrue(new ElevatorCommand(elevatorSubsystem, 5)); } } diff --git a/src/main/java/frc/robot/Subsystems/ElevatorSubsystem.java b/src/main/java/frc/robot/Subsystems/ElevatorSubsystem.java index 3d90dbc..86e4cfd 100644 --- a/src/main/java/frc/robot/Subsystems/ElevatorSubsystem.java +++ b/src/main/java/frc/robot/Subsystems/ElevatorSubsystem.java @@ -3,6 +3,7 @@ // the WPILib BSD license file in the root directory of this project. package frc.robot.Subsystems; +import com.ctre.phoenix.motorcontrol.TalonFXControlMode; import com.ctre.phoenix.motorcontrol.can.TalonFX; import edu.wpi.first.math.controller.PIDController; @@ -48,6 +49,7 @@ public void periodic() { motorPower = controller.calculate(targetHeight); leftMotor.set(TalonFXControlMode.PercentOutput, motorPower); + rightMotor.set(TalonFXControlMode.PercentOutput, motorPower); currentHeight = ticksToInches(-leftMotor.getSelectedSensorPosition()); }