Skip to content

Commit

Permalink
maybe run intake
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexDvorak committed Feb 25, 2024
1 parent 1791983 commit 2515ae6
Show file tree
Hide file tree
Showing 6 changed files with 31 additions and 278 deletions.
47 changes: 10 additions & 37 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -112,36 +112,14 @@ public RobotContainer() {
new ModuleIOSparkMax(2),
new ModuleIOSparkMax(3));
sFlywheel = new Flywheel(new FlywheelIOSparkMax());
sIntake = new Intake(new IntakeIOSparkMax() {});
sIntake = new Intake();
sArm = new Arm(new ArmIOSparkMax() {});
sArmElevator = new ArmElevator(new ArmElevatorIOSparkMax() {});
sWrist = new Wrist(new WristIOSparkMax() {});
sClimber = new Climber(new ClimberIOSparkMax() {});
// sSticks = new Sticks(new SticksIOSparkMax() {});

break;

case SIM:
// Sim robot, instantiate physics sim IO implementations
// Note that most of these are broken and useless, and I don't think we have time to fix
// them
sDrive =
new Drive(
new GyroIO() {},
new ModuleIOSim(),
new ModuleIOSim(),
new ModuleIOSim(),
new ModuleIOSim());
sFlywheel = new Flywheel(new FlywheelIOSim());
sIntake = new Intake(new IntakeIOSim() {});
sArm = new Arm(new ArmIOSim() {});
sArmElevator = new ArmElevator(new ArmElevatorIOSim() {});
sWrist = new Wrist(new WristIOSim() {});
sClimber = new Climber(new ClimberIOSim() {});
// sSticks = new Sticks(new SticksIOSim() {});

break;

default:
// Replayed robot, disable IO implementations
sDrive =
Expand All @@ -152,7 +130,7 @@ public RobotContainer() {
new ModuleIO() {},
new ModuleIO() {});
sFlywheel = new Flywheel(new FlywheelIO() {});
sIntake = new Intake(new IntakeIO() {});
sIntake = new Intake();
sArm = new Arm(new ArmIO() {});
sArmElevator = new ArmElevator(new ArmElevatorIO() {});
sWrist = new Wrist(new WristIO() {});
Expand All @@ -171,12 +149,7 @@ public RobotContainer() {
.withTimeout(5.0));

NamedCommands.registerCommand(
"Run Intake",
Commands.startEnd(
() -> sIntake.runVelocity(Constants.IntakeConstants.velocity),
sIntake::stop,
sIntake)
.withTimeout(5.0));
"Run Intake", Commands.startEnd(() -> sIntake.setPercent(0.5), sIntake::stop, sIntake));

// Build SmartDashboard auto chooser
if (!AutoBuilder.isConfigured()) {
Expand Down Expand Up @@ -291,13 +264,13 @@ private void configureButtonBindings() {
// () -> operatorController.getLeftTriggerAxis(),
// () -> operatorController.getRightTriggerAxis()));

sIntake.setDefaultCommand(
IntakeShooterControls.intakeShooterDrive(
sIntake,
sFlywheel,
() -> operatorController.getLeftTriggerAxis(),
() -> operatorController.getRightTriggerAxis(),
operatorController.leftBumper()));
// sIntake.setDefaultCommand(
// IntakeShooterControls.intakeShooterDrive(
// sIntake,
// sFlywheel,
// () -> operatorController.getLeftTriggerAxis(),
// () -> operatorController.getRightTriggerAxis(),
// operatorController.leftBumper()));
operatorController
.a()
.whileTrue(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,15 +42,15 @@ public static Command intakeShooterDrive(

if (Math.abs(flywheel.getVelocityRPMBottom())
> Math.abs(Constants.FlywheelConstants.shootingVelocity + 2000)) {
intake.runVelocity(Constants.IntakeConstants.velocity * 5);
intake.setPercent(.70); // ALEX
}

} else {
flywheel.runVelocity(0);
double stickMagnitude =
MathUtil.applyDeadband(leftTriggerSupplier.getAsDouble(), DEADBAND)
+ -MathUtil.applyDeadband(rightTriggerSupplier.getAsDouble(), DEADBAND);
intake.runVelocity(Constants.IntakeConstants.velocity * stickMagnitude);
intake.setPercent(0.70 * stickMagnitude); // ALEX
}
},
intake,
Expand Down
86 changes: 18 additions & 68 deletions src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
@@ -1,85 +1,35 @@
// Copyright 2021-2024 FRC 6328, FRC 5829
// http://github.com/Mechanical-Advantage
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
// version 3 as published by the Free Software Foundation or
// available in the root directory of this project.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.intake;

import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.util.Units;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.Constants.EnvironmentalConstants;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
import frc.robot.Constants.IntakeConstants;

public class Intake extends SubsystemBase {
private final IntakeIO io;
private final IntakeIOInputsAutoLogged inputs = new IntakeIOInputsAutoLogged();
private final SimpleMotorFeedforward ffModel;
// private static final double GEAR_RATIO = 52.0 / 34.0; // May be reciprocal

/** Creates a new Flywheel. */
public Intake(IntakeIO io) {
this.io = io;
private final CANSparkMax intakeMotor =
new CANSparkMax(IntakeConstants.kIntakeSparkMaxCanId, MotorType.kBrushless);
private final CANSparkMax followerIntakeMotor =
new CANSparkMax(IntakeConstants.kFollowerIntakeSparkMaxCanId, MotorType.kBrushless);

io.configurePID(
Constants.IntakeConstants.kP, Constants.IntakeConstants.kI, Constants.IntakeConstants.kD);
public Intake() {
intakeMotor.restoreFactoryDefaults();
followerIntakeMotor.restoreFactoryDefaults();

switch (EnvironmentalConstants.currentMode) {
case REAL:
case REPLAY:
ffModel = new SimpleMotorFeedforward(0.1, 0.05);
break;
case SIM:
ffModel = new SimpleMotorFeedforward(0.0, 0.03);
break;
default:
ffModel = new SimpleMotorFeedforward(0.0, 0.0);
break;
}
}
intakeMotor.setInverted(false);

@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Intake", inputs);
}
followerIntakeMotor.follow(intakeMotor, false);

/** Run open loop at the specified voltage. */
public void runVolts(double volts) {
io.setVoltage(volts);
intakeMotor.burnFlash();
followerIntakeMotor.burnFlash();
}

/** Run closed loop at the specified velocity. */
public void runVelocity(double velocityRPM) {
var velocityRadPerSec = Units.rotationsPerMinuteToRadiansPerSecond(velocityRPM);
io.setVelocity(velocityRadPerSec, ffModel.calculate(velocityRadPerSec));

// Log flywheel setpoint
Logger.recordOutput("Intake/SetpointRPM", velocityRPM);
public void setPercent(double pct) {
intakeMotor.set(pct);
}

/** Stops the flywheel. */
public void stop() {
io.stop();
}

/** Returns the current velocity in RPM. */
@AutoLogOutput
public double getVelocityRPM() {
return Units.radiansPerSecondToRotationsPerMinute(inputs.velocityRadPerSec);
}

/** Returns the current velocity in radians per second. */
public double getCharacterizationVelocity() {
return inputs.velocityRadPerSec;
intakeMotor.stopMotor();
}
}
5 changes: 1 addition & 4 deletions src/main/java/frc/robot/subsystems/intake/IntakeIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,7 @@

package frc.robot.subsystems.intake;

import org.littletonrobotics.junction.AutoLog;

public interface IntakeIO {
@AutoLog
public static class IntakeIOInputs {
public double positionRad = 0.0;
public double velocityRadPerSec = 0.0;
Expand All @@ -28,7 +25,7 @@ public static class IntakeIOInputs {
public default void updateInputs(IntakeIOInputs inputs) {}

/** Run open loop at the specified voltage. */
public default void setVoltage(double volts) {}
public default void setPercent(double volts) {}

/** Run closed loop at the specified velocity. */
public default void setVelocity(double velocityRadPerSec, double ffVolts) {}
Expand Down
68 changes: 0 additions & 68 deletions src/main/java/frc/robot/subsystems/intake/IntakeIOSim.java

This file was deleted.

99 changes: 0 additions & 99 deletions src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java

This file was deleted.

0 comments on commit 2515ae6

Please sign in to comment.