Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions .github/workflows/gradle-publish.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@ jobs:
distribution: 'adopt'
- name: Set Permissions
run: ls -lrt && chmod 777 ./*
- name: Clean Groovy
uses: gradle/gradle-build-action@4137be6a8bf7d7133955359dbd952c0ca73b1021
with:
arguments: :spotlessApply
- name: Build with Gradle
uses: gradle/gradle-build-action@4137be6a8bf7d7133955359dbd952c0ca73b1021
with:
Expand Down
14 changes: 14 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -1,4 +1,9 @@
{
"Joysticks": {
"window": {
"visible": false
}
},
"keyboardJoysticks": [
{
"axisConfig": [
Expand Down Expand Up @@ -88,5 +93,14 @@
"buttonCount": 0,
"povCount": 0
}
],
"robotJoysticks": [
{
"guid": "78696e70757401000000000000000000",
"useGamepad": true
},
{
"useGamepad": true
}
]
}
66 changes: 65 additions & 1 deletion simgui.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,71 @@
{
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo"
"/FMSInfo": "FMSInfo",
"/LiveWindow/AddressableLEDs": "Subsystem",
"/LiveWindow/BottomShooter": "Subsystem",
"/LiveWindow/BottomShooter/Bottom Shooter": "Subsystem",
"/LiveWindow/Chassis": "Subsystem",
"/LiveWindow/Feeder": "Subsystem",
"/LiveWindow/FrontClimber": "Subsystem",
"/LiveWindow/Intake": "Subsystem",
"/LiveWindow/RearClimber": "Subsystem",
"/LiveWindow/Shooter": "Subsystem",
"/LiveWindow/TopShooter/Top Shooter": "Subsystem",
"/LiveWindow/Ungrouped/DifferentialDrive[1]": "DifferentialDrive",
"/LiveWindow/Ungrouped/MotorControllerGroup[3]": "Motor Controller",
"/LiveWindow/Ungrouped/MotorControllerGroup[4]": "Motor Controller",
"/LiveWindow/Ungrouped/Scheduler": "Scheduler",
"/LiveWindow/Ungrouped/Talon FX [9]": "Motor Controller",
"/LiveWindow/Ungrouped/Talon SRX [5]": "Motor Controller",
"/LiveWindow/Ungrouped/Talon SRX [6]": "Motor Controller",
"/LiveWindow/Ungrouped/Talon SRX [7]": "Motor Controller",
"/LiveWindow/Ungrouped/Talon SRX [8]": "Motor Controller",
"/LiveWindow/Ungrouped/navX-Sensor[4]": "Gyro"
}
},
"NetworkTables": {
"FMSInfo": {
"open": true
},
"LiveWindow": {
"BottomShooter": {
"Bottom Shooter": {
"open": true
},
"open": true
},
"TopShooter": {
"Top Shooter": {
"open": true
},
"open": true
},
"Ungrouped": {
"DifferentialDrive[1]": {
"open": true
},
"MotorControllerGroup[3]": {
"open": true
},
"Talon FX [9]": {
"open": true
},
"Talon SRX [5]": {
"open": true
},
"Talon SRX [6]": {
"open": true
},
"Talon SRX [7]": {
"open": true
},
"Talon SRX [8]": {
"open": true
},
"open": true
},
"open": true
}
}
}
1 change: 0 additions & 1 deletion src/main/java/com/fireteam322/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ public final class Constants {
// Shooter.java
public static final int LEFT_SHOOTER_MOTOR = 7;
public static final int RIGHT_SHOOTER_MOTOR = 8;
public static final int TOP_SHOOTER_MOTOR = 9;

// RobotContainer.java
public static final int DRIVE_STICK = 0,
Expand Down
50 changes: 40 additions & 10 deletions src/main/java/com/fireteam322/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,9 @@ public class RobotContainer {
private final FrontClimber m_frontClimber = new FrontClimber();
private final Feeder m_feeder = new Feeder();
private final Intake m_intake = new Intake();
private final Shooter m_shooter = new Shooter();
// private final Shooter m_shooter = new Shooter();
private final TopShooter t_shooter = new TopShooter();
private final BottomShooter b_shooter = new BottomShooter();

private final F310Controller m_driveStick = new F310Controller(Constants.DRIVE_STICK);
private final F310Controller m_manipulatorStick = new F310Controller(Constants.MANIPULATOR_STICK);
Expand All @@ -50,14 +52,25 @@ public class RobotContainer {
new JoystickButton(m_driveStick, F310Controller.Button.kY.getValue());
private final JoystickButton m_frontClimbReverseButton =
new JoystickButton(m_driveStick, F310Controller.Button.kB.getValue());

// Feeder Buttons
private final JoystickButton m_feederButton =
new JoystickButton(m_manipulatorStick, F310Controller.Button.kA.getValue());

private final JoystickButton m_feederReverseButton =
new JoystickButton(m_manipulatorStick, F310Controller.Button.kB.getValue());

// Bottom Shooter
private final JoystickButton m_shooterButton =
new JoystickButton(m_manipulatorStick, F310Controller.Button.kX.getValue());

private final JoystickButton m_shooterReverseButton =
new JoystickButton(m_manipulatorStick, F310Controller.Button.kY.getValue());

// Top Shooter
private final JoystickButton m_topShooterButton =
new JoystickButton(m_driveStick, F310Controller.Button.kBumperLeft.getValue());

private final JoystickButton m_intakeReverseButton =
new JoystickButton(m_manipulatorStick, F310Controller.Button.kBumperLeft.getValue());
private final JoystickButton m_intakeButton =
Expand All @@ -80,12 +93,17 @@ public RobotContainer() {

m_intake.setDefaultCommand(new RunIntake(m_intake, () -> -m_manipulatorStick.getRightY()));

m_shooter.setDefaultCommand(
new RunShooter(
m_shooter,
() ->
(m_manipulatorStick.getRightTriggerAxis()
- m_manipulatorStick.getLeftTriggerAxis())));
/// t_shooter.getDefaultCommand(new RunTopShooter(t_shooter,m_manipulatorStick.getLeftX()));

// b_shooter.getDefaultCommand(new
// RunBottomShooter(b_shooter,m_manipulatorStick.getLeftTriggerAxis()));*/

/* m_shooter.setDefaultCommand(
new RunShooter(
m_shooter,
() ->
(m_manipulatorStick.getRightTriggerAxis()
- m_manipulatorStick.getLeftTriggerAxis())));*/

m_frontClimber.setDefaultCommand(
new RunFrontClimber(m_frontClimber, m_manipulatorStick.getLeftX()));
Expand Down Expand Up @@ -115,9 +133,21 @@ private void configureButtonBindings() {
m_feederReverseButton.whileActiveOnce(
new RunFeeder(m_feeder, () -> Constants.FEEDER_REVERSE_SPEED), true);

m_shooterButton.whileActiveOnce(new RunShooter(m_shooter, () -> Constants.SHOOTER_SPEED), true);
m_shooterReverseButton.whileActiveOnce(
new RunShooter(m_shooter, () -> Constants.SHOOTER_REVERSE_SPEED), true);
/*m_shooterButton.whileActiveOnce(new RunShooter(m_shooter, () -> Constants.SHOOTER_SPEED), true);*/

// Bottom Shooter
m_shooterButton.whileHeld(new RunBottomShooter(b_shooter, Constants.SHOOTER_SPEED), true);
m_shooterButton.whenReleased(new RunBottomShooter(b_shooter, 0), true);
m_shooterReverseButton.whileHeld(
new RunBottomShooter(b_shooter, Constants.SHOOTER_REVERSE_SPEED), true);
m_shooterReverseButton.whenReleased(new RunBottomShooter(b_shooter, 0), true);

// Top Shooter
m_topShooterButton.whileHeld(new RunTopShooter(t_shooter, Constants.SHOOTER_SPEED), true);
m_topShooterButton.whenReleased(new RunTopShooter(t_shooter, 0), true);

/* m_shooterReverseButton.whileActiveOnce(
new RunShooter(m_shooter, () -> Constants.SHOOTER_REVERSE_SPEED), true);*/

m_intakeButton.whileActiveOnce(new RunIntake(m_intake, () -> Constants.INTAKE_SPEED));
m_intakeReverseButton.whileActiveOnce(
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package com.fireteam322.frc.robot.commands;

import com.fireteam322.frc.robot.subsystems.BottomShooter;
import edu.wpi.first.wpilibj2.command.CommandBase;

public class RunBottomShooter extends CommandBase {
private final BottomShooter m_shooter;
private final double m_speed;

/** Creates a new RunShooter. */
public RunBottomShooter(BottomShooter shooter, double speed) {
m_shooter = shooter;
m_speed = speed;
// Use addRequirements() here to declare subsystem dependencies.
m_shooter.setName("Bottom Shooter");
addRequirements(m_shooter);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_shooter.run(m_speed);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
if (!interrupted) m_shooter.stop();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package com.fireteam322.frc.robot.commands;

import com.fireteam322.frc.robot.subsystems.TopShooter;
import edu.wpi.first.wpilibj2.command.CommandBase;

public class RunTopShooter extends CommandBase {
private final TopShooter m_shooter;
private final double m_speed;

/** Creates a new RunShooter. */
public RunTopShooter(TopShooter shooter, double speed) {
m_shooter = shooter;
m_speed = speed;
m_shooter.setName("Top Shooter");
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(m_shooter);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_shooter.run(m_speed);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
if (!interrupted) m_shooter.stop();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
package com.fireteam322.frc.robot.subsystems;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.fireteam322.frc.robot.Constants;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class BottomShooter extends SubsystemBase {
// The Shooter is both our upper level ball intake and our ball output
// mechanism.
private final WPI_TalonSRX m_leftShooterMotor = new WPI_TalonSRX(Constants.LEFT_SHOOTER_MOTOR);

/** Creates a new Shooter. */
public BottomShooter() {
super();
// Set the inversion on the shooter motors.
m_leftShooterMotor.setInverted(false);

// Set the shooter motors to Coast so they don't stop balls moving through them.
m_leftShooterMotor.setNeutralMode(NeutralMode.Brake);
}

public void stop() {
m_leftShooterMotor.stopMotor();
}

public void run(double speed) {
m_leftShooterMotor.set(speed);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -18,24 +18,21 @@ public class Shooter extends SubsystemBase {
// mechanism.
private final WPI_TalonSRX m_leftShooterMotor = new WPI_TalonSRX(Constants.LEFT_SHOOTER_MOTOR);
private final WPI_TalonSRX m_rightShooterMotor = new WPI_TalonSRX(Constants.RIGHT_SHOOTER_MOTOR);
private final WPI_TalonSRX m_topShooterMotor = new WPI_TalonSRX(Constants.TOP_SHOOTER_MOTOR);

private final MotorControllerGroup m_shooterMotors =
new MotorControllerGroup(m_leftShooterMotor, m_rightShooterMotor, m_topShooterMotor);
new MotorControllerGroup(m_leftShooterMotor, m_rightShooterMotor);

/** Creates a new Shooter. */
public Shooter() {
super();
// Set the inversion on the shooter motors.
m_leftShooterMotor.setInverted(false);
m_rightShooterMotor.setInverted(false);
m_topShooterMotor.setInverted(true);
m_shooterMotors.setInverted(true);

// Set the shooter motors to Coast so they don't stop balls moving through them.
m_leftShooterMotor.setNeutralMode(NeutralMode.Coast);
m_rightShooterMotor.setNeutralMode(NeutralMode.Coast);
m_topShooterMotor.setNeutralMode(NeutralMode.Coast);
}

public void stop() {
Expand Down
36 changes: 36 additions & 0 deletions src/main/java/com/fireteam322/frc/robot/subsystems/TopShooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
package com.fireteam322.frc.robot.subsystems;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.fireteam322.frc.robot.Constants;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class TopShooter extends SubsystemBase {
// The Shooter is both our upper level ball intake and our ball output
// mechanism.
private final WPI_TalonSRX m_rightShooterMotor = new WPI_TalonSRX(Constants.RIGHT_SHOOTER_MOTOR);

/** Creates a new Shooter. */
public TopShooter() {
super();
// Set the inversion on the shooter motors.

m_rightShooterMotor.setInverted(false);

// Set the shooter motors to Coast so they don't stop balls moving through them.
m_rightShooterMotor.setNeutralMode(NeutralMode.Brake);
}

public void stop() {
m_rightShooterMotor.stopMotor();
}

public void run(double speed) {
m_rightShooterMotor.set(speed);
}

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