Skip to content

Commit

Permalink
Add subsystems, update constants
Browse files Browse the repository at this point in the history
Added intake, dump, and conveyor subsystems. These closely mirror those found on OakvilleDynamics/2024-Robot.

Updated constants to reflect better names of some of the variables.
  • Loading branch information
garrettsummerfi3ld committed Mar 2, 2024
1 parent 84dada5 commit 50e719b
Show file tree
Hide file tree
Showing 6 changed files with 182 additions and 35 deletions.
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -64,10 +64,10 @@ public static final class Intake {
* to match the physical properties of the conveyor.
*/
public static final class Conveyor {
public static final int CONVEYOR_MOTOR_1 = 1;
public static final int CONVEYOR_MOTOR_2 = 2;
public static final boolean CONVEYOR_MOTOR_1_INVERTED = true;
public static final boolean CONVEYOR_MOTOR_2_INVERTED = false;
public static final int CONVEYOR_MOTOR_LEFT = 1;
public static final int CONVEYOR_MOTOR_RIGHT = 2;
public static final boolean CONVEYOR_MOTOR_LEFT_INVERTED = true;
public static final boolean CONVEYOR_MOTOR_RIGHT_INVERTED = false;
public static final double CONVEYOR_MOTOR_SPEED = 0.38;
}
}
Expand Down
46 changes: 24 additions & 22 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,12 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants.OperatorConstants;
import frc.robot.subsystems.ConveyorSubsystem;
import frc.robot.subsystems.DumpSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.swerve.SwerveSubsystem;
import java.io.File;

Expand All @@ -28,11 +32,17 @@ public class RobotContainer {
// The robot's subsystems and commands are defined here...
private final SwerveSubsystem drivebase =
new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "swerve"));
private final IntakeSubsystem intake = new IntakeSubsystem();
private final ConveyorSubsystem conveyor = new ConveyorSubsystem();
private final DumpSubsystem dump = new DumpSubsystem();

// Replace with CommandPS4Controller or CommandJoystick if needed
final CommandXboxController driverXbox = new CommandXboxController(0);
// Controllers and joysticks are defined here
final CommandXboxController driverXbox = new CommandXboxController(Constants.OperatorConstants.Joysticks.Port.DRIVER_CONTROLLER);
final CommandJoystick copilotJoystick = new CommandJoystick(Constants.OperatorConstants.Joysticks.Port.COPILOT_CONTROLLER);

/** The container for the robot. Contains subsystems, OI devices, and commands. */
/**
* The container for the robot. Contains subsystems, OI devices, and commands.
*/
public RobotContainer() {
// Configure the trigger bindings
configureBindings();
Expand Down Expand Up @@ -60,6 +70,7 @@ public RobotContainer() {
() -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.Deadbands.LEFT_X),
() -> driverXbox.getRightX() * 0.5);

drivebase.setMotorBrake(true);
drivebase.setDefaultCommand(driveFieldOrientedDirectAngle);
}

Expand All @@ -73,18 +84,17 @@ public RobotContainer() {
* joysticks}.
*/
private void configureBindings() {
// Schedule `ExampleCommand` when `exampleCondition` changes to `true`

driverXbox.a().onTrue((Commands.runOnce(drivebase::zeroGyro)));
driverXbox.a().onTrue(Commands.runOnce(drivebase::zeroGyro));
driverXbox.x().onTrue(Commands.runOnce(drivebase::addFakeVisionReading));
driverXbox
.b()
.whileTrue(
Commands.deferredProxy(
() ->
drivebase.driveToPose(
new Pose2d(new Translation2d(4, 4), Rotation2d.fromDegrees(0)))));
// driverXbox.x().whileTrue(Commands.runOnce(drivebase::lock, drivebase).repeatedly());
driverXbox.b().whileTrue(Commands.deferredProxy(() -> drivebase.driveToPose(new Pose2d(new Translation2d(4, 4), Rotation2d.fromDegrees(0)))));
driverXbox.y().whileTrue(Commands.runOnce(drivebase::lock, drivebase).repeatedly());

copilotJoystick.trigger().onTrue(Commands.runOnce(dump::dump));
copilotJoystick.trigger().onFalse(Commands.runOnce(dump::retract));
copilotJoystick.button(3).whileTrue(Commands.runOnce(intake::runIntake));
copilotJoystick.button(4).whileTrue(Commands.runOnce(intake::reverseIntake));
copilotJoystick.button(5).whileTrue(Commands.runOnce(conveyor::runConveyor));
copilotJoystick.button(6).whileTrue(Commands.runOnce(conveyor::reverseConveyor));
}

/**
Expand All @@ -96,12 +106,4 @@ public Command getAutonomousCommand() {
// An example command will be run in autonomous
return drivebase.getAutonomousCommand("New Auto");
}

public void setDriveMode() {
// drivebase.setDefaultCommand();
}

public void setMotorBrake(boolean brake) {
drivebase.setMotorBrake(brake);
}
}
52 changes: 52 additions & 0 deletions src/main/java/frc/robot/subsystems/ConveyorSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
// 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.subsystems;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.MechanismConstants.Conveyor;

public class ConveyorSubsystem extends SubsystemBase {
private final CANSparkMax conveyorMotorLeft = new CANSparkMax(Conveyor.CONVEYOR_MOTOR_LEFT, MotorType.kBrushless);
private final CANSparkMax conveyorMotorRight = new CANSparkMax(Conveyor.CONVEYOR_MOTOR_RIGHT, MotorType.kBrushless);

public ConveyorSubsystem() {
conveyorMotorLeft.setInverted(Conveyor.CONVEYOR_MOTOR_LEFT_INVERTED);
conveyorMotorRight.setInverted(Conveyor.CONVEYOR_MOTOR_RIGHT_INVERTED);

conveyorMotorLeft.setIdleMode(IdleMode.kBrake);
conveyorMotorRight.setIdleMode(IdleMode.kBrake);
}

@Override
public void periodic() {}

/**
* Run the conveyor at a set speed in the {@link Conveyor} class.
*/
public void runConveyor() {
conveyorMotorLeft.set(Conveyor.CONVEYOR_MOTOR_SPEED);
conveyorMotorRight.set(Conveyor.CONVEYOR_MOTOR_SPEED);
}

/**
* Stop the conveyor.
*/
public void stopConveyor() {
conveyorMotorLeft.set(0);
conveyorMotorRight.set(0);
}

/**
* Reverse the conveyor at a set speed in the {@link Conveyor} class.
*/
public void reverseConveyor() {
conveyorMotorLeft.set(-Conveyor.CONVEYOR_MOTOR_SPEED);
conveyorMotorRight.set(-Conveyor.CONVEYOR_MOTOR_SPEED);
}
}
42 changes: 42 additions & 0 deletions src/main/java/frc/robot/subsystems/DumpSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// 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.subsystems;

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.HardwareConstants;

public class DumpSubsystem extends SubsystemBase {
private final DoubleSolenoid dumpSolenoid = new DoubleSolenoid(HardwareConstants.REV_PCM_ID, PneumaticsModuleType.REVPH, HardwareConstants.PneumaticsChannel.DUMP_OUT, HardwareConstants.PneumaticsChannel.DUMP_IN);
private boolean isDumped = false;

public DumpSubsystem() {
SmartDashboard.putBoolean(getName(), isDumped);
}

@Override
public void periodic() {
}

/**
* Dumps the dump bed.
*/
public void dump() {
dumpSolenoid.set(DoubleSolenoid.Value.kForward);
isDumped = true;
SmartDashboard.putBoolean(getName(), isDumped);
}

/**
* Retracts the dump bed.
*/
public void retract() {
dumpSolenoid.set(DoubleSolenoid.Value.kReverse);
isDumped = false;
SmartDashboard.putBoolean(getName(), isDumped);
}
}
53 changes: 53 additions & 0 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
// 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.subsystems;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
import frc.robot.Constants.MechanismConstants.Intake;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class IntakeSubsystem extends SubsystemBase {
private final CANSparkMax intakeSushi = new CANSparkMax(Intake.INTAKE_SUSHI, MotorType.kBrushless);
private final CANSparkMax intakeFront = new CANSparkMax(Intake.INTAKE_FRONT, MotorType.kBrushless);

public IntakeSubsystem() {
intakeSushi.setInverted(Intake.INTAKE_SUSHI_INVERTED);
intakeFront.setInverted(Intake.INTAKE_FRONT_INVERTED);

intakeFront.setIdleMode(IdleMode.kBrake);
intakeSushi.setIdleMode(IdleMode.kBrake);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}

/**
* Run the intake at a set speed in the {@link Intake} class.
*/
public void runIntake() {
intakeSushi.set(Intake.INTAKE_SUSHI_SPEED);
intakeFront.set(Intake.INTAKE_FRONT_SPEED);
}

/**
* Stop the intake.
*/
public void stopIntake() {
intakeSushi.set(0);
intakeFront.set(0);
}

/**
* Reverse the intake at a set speed in the {@link Intake} class.
*/
public void reverseIntake() {
intakeSushi.set(-Intake.INTAKE_SUSHI_SPEED);
intakeFront.set(-Intake.INTAKE_FRONT_SPEED);
}
}
16 changes: 7 additions & 9 deletions src/main/java/frc/robot/subsystems/swerve/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -72,12 +72,10 @@ public SwerveSubsystem(File directory) {
} catch (Exception e) {
throw new RuntimeException(e);
}
swerveDrive.setHeadingCorrection(
false); // Heading correction should only be used while controlling the robot via angle.
swerveDrive.setCosineCompensator(
!SwerveDriveTelemetry
.isSimulation); // Disables cosine compensation for simulations since it causes
// discrepancies not seen in real life.
// Heading correction should only be used while controlling the robot via angle.
swerveDrive.setHeadingCorrection(false);
// Disables cosine compensation for simulations since it causes discrepancies not seen in real life.
swerveDrive.setCosineCompensator(!SwerveDriveTelemetry.isSimulation);
setupPathPlanner();
}

Expand All @@ -95,7 +93,7 @@ public SwerveSubsystem(
/** Setup AutoBuilder for PathPlanner. */
public void setupPathPlanner() {
AutoBuilder.configureHolonomic(
this::getPose, // Robot pose supplier
this::getPose,// Robot pose supplier
this::resetOdometry, // Method to reset odometry (will be called if your auto has a starting
// pose)
this::getRobotVelocity, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
Expand Down Expand Up @@ -202,8 +200,8 @@ public Command driveCommand(
// this kind of control.
return run(
() -> {
double xInput = Math.pow(translationX.getAsDouble(), 3); // Smooth controll out
double yInput = Math.pow(translationY.getAsDouble(), 3); // Smooth controll out
double xInput = Math.pow(translationX.getAsDouble(), 3); // Smooth control out
double yInput = Math.pow(translationY.getAsDouble(), 3); // Smooth control out
// Make the robot move
driveFieldOriented(
swerveDrive.swerveController.getTargetSpeeds(
Expand Down

0 comments on commit 50e719b

Please sign in to comment.