From ba548a447a64db7e07cd2825250c747a5d8e761c Mon Sep 17 00:00:00 2001 From: Tyler-J42 Date: Sat, 17 Feb 2024 13:47:34 -0500 Subject: [PATCH] manual testing controls --- .SysId/sysid.json | 1 + src/main/java/frc/robot/RobotContainer.java | 6 ++++-- src/main/java/frc/robot/constants/IntakeConstants.java | 4 ++-- src/main/java/frc/robot/subsystems/Intake.java | 8 ++++++++ src/main/java/frc/robot/subsystems/Shooter.java | 7 +++++++ 5 files changed, 22 insertions(+), 4 deletions(-) create mode 100644 .SysId/sysid.json diff --git a/.SysId/sysid.json b/.SysId/sysid.json new file mode 100644 index 0000000..0967ef4 --- /dev/null +++ b/.SysId/sysid.json @@ -0,0 +1 @@ +{} diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1a2fa2e..a08c4df 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -132,9 +132,11 @@ public class RobotContainer { ) ); - intake.setDefaultCommand(intake.intakeUpCommand()); + //intake.setDefaultCommand(intake.intakeUpCommand()); + intake.setDefaultCommand(intake.manualPivot(operator::getLeftY)); - shooter.setDefaultCommand(shooter.angleSpeedsSetpoints(ShooterConstants.kShooterLoadAngle, 0.0, 0.0)); + // shooter.setDefaultCommand(shooter.angleSpeedsSetpoints(ShooterConstants.kShooterLoadAngle, 0.0, 0.0)); + shooter.setDefaultCommand(shooter.manualPivot(operator::getRightY); climber.setDefaultCommand(climber.stop()); diff --git a/src/main/java/frc/robot/constants/IntakeConstants.java b/src/main/java/frc/robot/constants/IntakeConstants.java index d1b3a4e..cef8e8e 100644 --- a/src/main/java/frc/robot/constants/IntakeConstants.java +++ b/src/main/java/frc/robot/constants/IntakeConstants.java @@ -1,8 +1,8 @@ package frc.robot.constants; public class IntakeConstants { - public static final int kIntakePivotID = 9; - public static final int kIntakeRollerID = 10; + public static final int kIntakePivotID = 10; + public static final int kIntakeRollerID = 12; public static final double kIntakePivotConversionFactor = 1/(20.0*(28.0/15.0)); diff --git a/src/main/java/frc/robot/subsystems/Intake.java b/src/main/java/frc/robot/subsystems/Intake.java index f498a2a..5e80fe9 100644 --- a/src/main/java/frc/robot/subsystems/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake.java @@ -1,5 +1,7 @@ package frc.robot.subsystems; +import java.util.function.DoubleSupplier; + import com.revrobotics.CANSparkMax; import com.revrobotics.RelativeEncoder; import com.revrobotics.CANSparkBase.IdleMode; @@ -68,6 +70,12 @@ public class Intake extends SubsystemBase{ }); } + public Command manualPivot(DoubleSupplier pivotPower){ + return run(() ->{ + intakePivot.set(pivotPower.getAsDouble()); + }); + } + public Command climbingStateCommand() { return run(() -> { intakeRoller.set(0.0); diff --git a/src/main/java/frc/robot/subsystems/Shooter.java b/src/main/java/frc/robot/subsystems/Shooter.java index 98f39a9..04bfc75 100644 --- a/src/main/java/frc/robot/subsystems/Shooter.java +++ b/src/main/java/frc/robot/subsystems/Shooter.java @@ -131,4 +131,11 @@ public class Shooter extends SubsystemBase{ public DoubleSupplier getShooterAngle(){ return () -> {return pivotEncoder.getDistance();}; } + + public Command manualPivot(DoubleSupplier pivotPower){ + return run(() ->{ + shooterPivot.set(pivotPower.getAsDouble()); + }); + } + }