Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Refactor to use command factories instead of public methods #1

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
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
18 changes: 5 additions & 13 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,8 @@

package frc.robot;

import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.subsystems.DriveSubsystem;

Expand All @@ -17,17 +14,12 @@ public class RobotContainer {
private final DriveSubsystem driveSubsystem = new DriveSubsystem();

public RobotContainer() {
driveSubsystem.setDefaultCommand(
new RunCommand(
() -> driveSubsystem.driveArcade(driverXbox.getLeftY(),driverXbox.getLeftX()),
driveSubsystem
)
);
driverXbox.leftBumper().onTrue(new InstantCommand(() -> driveSubsystem.shiftGearHighSpeed()));
driverXbox.rightBumper().onTrue(new InstantCommand(() -> driveSubsystem.shiftGearLowSpeed()));

driveSubsystem.setDefaultCommand(driveSubsystem.driveArcadeCommand(driverXbox::getLeftX, () -> {
return driverXbox.getLeftY() * -1.0;
}));
driverXbox.leftBumper().onTrue(driveSubsystem.shiftHighCommand());
driverXbox.rightBumper().onTrue(driveSubsystem.shiftLowCommand());
}


public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
Expand Down
149 changes: 81 additions & 68 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
package frc.robot.subsystems;

import java.util.function.DoubleSupplier;

import com.ctre.phoenix.motorcontrol.FeedbackDevice;
import com.ctre.phoenix.motorcontrol.InvertType;
import com.ctre.phoenix.motorcontrol.NeutralMode;
Expand All @@ -8,74 +10,85 @@
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticHub;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem;

public class DriveSubsystem implements Subsystem{
private final WPI_TalonSRX m_leftMotorLeader = new WPI_TalonSRX(10);
private final WPI_TalonSRX m_leftMotorFollower = new WPI_TalonSRX(11);
private final WPI_TalonSRX m_rightMotorLeader = new WPI_TalonSRX(12);
private final WPI_TalonSRX m_rightMotorFollower = new WPI_TalonSRX(13);

private final PneumaticHub m_pH = new PneumaticHub(1);
private final DoubleSolenoid m_solnoidLeft = m_pH.makeDoubleSolenoid(0,1);
private final DoubleSolenoid m_solnoidRight = m_pH.makeDoubleSolenoid(2,3);
private boolean m_isGearedFast = false;

private DifferentialDrive m_robotDrive;

public DriveSubsystem() {
m_leftMotorFollower.follow(m_leftMotorLeader);
m_rightMotorFollower.follow(m_rightMotorLeader);

m_rightMotorLeader.configPeakCurrentLimit(25);
m_leftMotorLeader.configPeakCurrentLimit(25);
m_rightMotorFollower.configPeakCurrentLimit(25);
m_leftMotorFollower.configPeakCurrentLimit(25);

m_rightMotorLeader.setNeutralMode(NeutralMode.Brake);
m_leftMotorLeader.setNeutralMode(NeutralMode.Brake);
m_rightMotorFollower.setNeutralMode(NeutralMode.Brake);
m_leftMotorFollower.setNeutralMode(NeutralMode.Brake);

m_rightMotorLeader.setInverted(true);
m_leftMotorFollower.setInverted(InvertType.FollowMaster);
m_rightMotorFollower.setInverted(InvertType.FollowMaster);

m_rightMotorLeader.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, 0, 10);
m_leftMotorLeader.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, 0, 10);


m_rightMotorLeader.config_kP(0, 1.0);
m_rightMotorLeader.config_kI(0, 0.000001);

m_leftMotorLeader.config_kP(0, 1.0);
m_leftMotorLeader.config_kI(0, 0.000001);

shiftGearLowSpeed();

m_robotDrive = new DifferentialDrive(m_leftMotorLeader, m_rightMotorLeader);
}
public void shiftGearHighSpeed() {
m_isGearedFast = true;
m_solnoidLeft.set(DoubleSolenoid.Value.kReverse);
m_solnoidRight.set(DoubleSolenoid.Value.kReverse);
}
public void shiftGearLowSpeed() {
m_isGearedFast = false;
m_solnoidLeft.set(DoubleSolenoid.Value.kForward);
m_solnoidRight.set(DoubleSolenoid.Value.kForward);
}

public void driveArcade(double forward, double turn) {
m_robotDrive.arcadeDrive(forward, turn);
}

public void driveTank(double left, double right) {
m_robotDrive.tankDrive(left, right);
}

@Override
public void periodic() {
}
public class DriveSubsystem implements Subsystem {
private final WPI_TalonSRX m_leftMotorLeader = new WPI_TalonSRX(10);
private final WPI_TalonSRX m_leftMotorFollower = new WPI_TalonSRX(11);
private final WPI_TalonSRX m_rightMotorLeader = new WPI_TalonSRX(12);
private final WPI_TalonSRX m_rightMotorFollower = new WPI_TalonSRX(13);

private final PneumaticHub m_pH = new PneumaticHub(1);
private final DoubleSolenoid m_solnoidLeft = m_pH.makeDoubleSolenoid(0, 1);
private final DoubleSolenoid m_solnoidRight = m_pH.makeDoubleSolenoid(2, 3);
private boolean m_isGearedFast = false;

private DifferentialDrive m_robotDrive;

public DriveSubsystem() {
m_leftMotorFollower.follow(m_leftMotorLeader);
m_rightMotorFollower.follow(m_rightMotorLeader);

m_rightMotorLeader.configPeakCurrentLimit(25);
m_leftMotorLeader.configPeakCurrentLimit(25);
m_rightMotorFollower.configPeakCurrentLimit(25);
m_leftMotorFollower.configPeakCurrentLimit(25);

m_rightMotorLeader.setNeutralMode(NeutralMode.Brake);
m_leftMotorLeader.setNeutralMode(NeutralMode.Brake);
m_rightMotorFollower.setNeutralMode(NeutralMode.Brake);
m_leftMotorFollower.setNeutralMode(NeutralMode.Brake);

m_rightMotorLeader.setInverted(true);
m_leftMotorFollower.setInverted(InvertType.FollowMaster);
m_rightMotorFollower.setInverted(InvertType.FollowMaster);

m_rightMotorLeader.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, 0, 10);
m_leftMotorLeader.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, 0, 10);

m_rightMotorLeader.config_kP(0, 1.0);
m_rightMotorLeader.config_kI(0, 0.000001);

m_leftMotorLeader.config_kP(0, 1.0);
m_leftMotorLeader.config_kI(0, 0.000001);

this.shiftLowCommand().execute();

m_robotDrive = new DifferentialDrive(m_leftMotorLeader, m_rightMotorLeader);
}

public Command shiftHighCommand() {
return runOnce(() -> {
m_isGearedFast = true;
m_solnoidLeft.set(DoubleSolenoid.Value.kReverse);
m_solnoidRight.set(DoubleSolenoid.Value.kReverse);
});
}

public Command shiftLowCommand() {
return runOnce(() -> {
m_isGearedFast = false;
m_solnoidLeft.set(DoubleSolenoid.Value.kForward);
m_solnoidRight.set(DoubleSolenoid.Value.kForward);
});
}

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nitpick: make it a little more clear that these shift the speed and not like height or something. It makes sense now but maybe not when I am sleep deprived

public Command driveArcadeCommand(DoubleSupplier forward, DoubleSupplier turn) {
return run(() -> m_robotDrive.arcadeDrive(forward.getAsDouble(), turn.getAsDouble()))
.withName("arcadeDrive");
}

public Command driveTankCommand(DoubleSupplier left, DoubleSupplier right) {
return run(() -> m_robotDrive.tankDrive(left.getAsDouble(), right.getAsDouble()))
.withName("tankDrive");
}

public void driveTank(double left, double right) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is there supposed to be one that isn't a command.

m_robotDrive.tankDrive(left, right);
}

@Override
public void periodic() {
}
}