Skip to content

Commit

Permalink
Add flywheels
Browse files Browse the repository at this point in the history
  • Loading branch information
OakvilleDynamicsProgrammer committed Mar 5, 2024
1 parent 82c0640 commit 32b7e6d
Show file tree
Hide file tree
Showing 4 changed files with 107 additions and 0 deletions.
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -85,5 +85,12 @@ public static class MechanismConstants {
public static final boolean CONVEYOR_MOTOR_1_INVERTED = true;
public static final boolean CONVEYOR_MOTOR_2_INVERTED = false;
public static final double CONVEYOR_MOTOR_SPEED = 0.38;

// Flywheel Motors
public static final int FLYWHEEL_MOTOR_1 = 3;
public static final int FLYWHEEL_MOTOR_2 = 4;
public static final boolean FLYWHEEL_MOTOR_1_INVERTED = true;
public static final boolean FLYWHEEL_MOTOR_2_INVERTED = false;
public static final double FLYWHEEL_MOTOR_SPEED = 0.8;
}
}
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,12 @@
import frc.robot.Constants.OperatorConstants;
import frc.robot.commands.ConveyorCommand;
import frc.robot.commands.DumpControl;
import frc.robot.commands.FlyWCommand;
import frc.robot.commands.IntakeCommand;
import frc.robot.commands.swervedrive.drivebase.AbsoluteDriveAdv;
import frc.robot.subsystems.Conveyor;
import frc.robot.subsystems.Dump;
import frc.robot.subsystems.FlyWheel;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.swervedrive.SwerveSubsystem;
import java.io.File;
Expand All @@ -50,13 +52,15 @@ public class RobotContainer {
private final Intake intake = new Intake();
private final Dump dump = new Dump();
private final Conveyor conveyor = new Conveyor();
private final FlyWheel flyWheel = new FlyWheel();

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {

intake.setDefaultCommand(new IntakeCommand(intake));
dump.setDefaultCommand(new DumpControl(dump));
conveyor.setDefaultCommand(new ConveyorCommand(conveyor));
flyWheel.setDefaultCommand(new FlyWCommand(flyWheel));

// Configure the trigger bindings
configureBindings();
Expand Down
49 changes: 49 additions & 0 deletions src/main/java/frc/robot/commands/FlyWCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
// 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.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.FlyWheel;

public class FlyWCommand extends Command {
private final FlyWheel m_FlyWSubsystem;
// controller
// TODO: Change this to the correct controller
private final Joystick ConveyorJoystick = new Joystick(1);

public FlyWCommand(FlyWheel subsystem) {
m_FlyWSubsystem = subsystem;
addRequirements(m_FlyWSubsystem);
}

@Override
public void initialize() {}

@Override
public void execute() {
// TODO: Change this to the correct button
if (ConveyorJoystick.getRawButton(3) == true) {

Check warning on line 28 in src/main/java/frc/robot/commands/FlyWCommand.java

View workflow job for this annotation

GitHub Actions / qodana

Pointless boolean expression

`ConveyorJoystick.getRawButton(3) == true` can be simplified to 'ConveyorJoystick.getRawButton(3)'
m_FlyWSubsystem.enableflywheel();
// TODO: Change this to the correct button
} else if (ConveyorJoystick.getRawButton(4) == true) {

Check warning on line 31 in src/main/java/frc/robot/commands/FlyWCommand.java

View workflow job for this annotation

GitHub Actions / qodana

Pointless boolean expression

`ConveyorJoystick.getRawButton(4) == true` can be simplified to 'ConveyorJoystick.getRawButton(4)'
m_FlyWSubsystem.reverseflywheel();
System.out.println("Conveyor Moving in Reverse");
} else {
m_FlyWSubsystem.disableflywheel();
}
}

@Override
public void end(boolean interrupted) {
m_FlyWSubsystem.disableflywheel();
m_FlyWSubsystem.enableflywheel();
}

@Override
public boolean isFinished() {
return false;
}
}
47 changes: 47 additions & 0 deletions src/main/java/frc/robot/subsystems/FlyWheel.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// 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.CANSparkLowLevel;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.MechanismConstants;

public class FlyWheel extends SubsystemBase {

private final CANSparkMax flywheelMotor1 =
new CANSparkMax(MechanismConstants.FLYWHEEL_MOTOR_1, CANSparkLowLevel.MotorType.kBrushless);
private final CANSparkMax flywheelMotor2 =
new CANSparkMax(MechanismConstants.FLYWHEEL_MOTOR_2, CANSparkLowLevel.MotorType.kBrushless);

/** Creates a new flywheel. */
public FlyWheel() {
flywheelMotor1.setInverted(MechanismConstants.FLYWHEEL_MOTOR_1_INVERTED);
flywheelMotor2.setInverted(MechanismConstants.FLYWHEEL_MOTOR_2_INVERTED);
}

/** Sets the flywheel motors to 100% power. */
public void enableflywheel() {
flywheelMotor1.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED);
flywheelMotor2.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED);
}

/** Sets the flywheel motors to 0% power. */
public void disableflywheel() {
flywheelMotor1.set(0);
flywheelMotor2.set(0);
}

/** Sets the flywheel motors to -100% power. (Reverse direction) */
public void reverseflywheel() {
flywheelMotor1.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED);
flywheelMotor2.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED);
}

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

0 comments on commit 32b7e6d

Please sign in to comment.