Skip to content

Commit

Permalink
Replaced drive motor and shooter motors from CANSparkMax to CANSparkF…
Browse files Browse the repository at this point in the history
…lex; added button bindings to all motors :3

Co-authored-by: hahafoot <[email protected]>
  • Loading branch information
jopy-wng and hahafoot committed Feb 15, 2024
1 parent cb83a9a commit bc9e9cd
Show file tree
Hide file tree
Showing 4 changed files with 70 additions and 13 deletions.
22 changes: 21 additions & 1 deletion src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,28 @@ private Command runMotorCommand(String name, DoubleConsumer set, Subsystem subsy
}

private void configureButtonBindings() {
driver.getTopButton()
driver.getLeftButton()
.whileTrue(runMotorCommand("Shooter left voltage", shooter::setLeftVoltage, shooter));
driver.getBottomButton()
.whileTrue(runMotorCommand("Shooter right voltage", shooter::setRightVoltage, shooter));
driver.getTopButton()
.whileTrue(runMotorCommand("Amper lift voltage", amper::setLiftVoltage, amper));
driver.getRightButton()
.whileTrue(runMotorCommand("Amper voltage", amper::setAmperVoltage, amper));
driver.getRightBumper()
.whileTrue(runMotorCommand("Gandalf voltage", conveyer::setGandalfVoltage, conveyer));
driver.getRightTriggerButton()
.whileTrue(runMotorCommand("Conveyor shooter feeder voltage", conveyer::setShooterFeederVoltage, conveyer));
driver.getStartButton()
.whileTrue(runMotorCommand("Intake voltage", intake::setIntakeVoltage, intake));
driver.getDPadLeft()
.whileTrue(runMotorCommand("Swerve turn voltage", swerve::setTurnVoltage, swerve));
driver.getDPadDown()
.whileTrue(runMotorCommand("Swerve drive voltage", swerve::setDriveVoltage, swerve));
driver.getDPadUp()
.whileTrue(runMotorCommand("Climber left voltage", climber::setLeftVoltage, swerve));
driver.getDPadRight()
.whileTrue(runMotorCommand("Climber right voltage", climber::setRightVoltage, climber));
}


Expand Down
46 changes: 41 additions & 5 deletions src/main/java/com/stuypulse/robot/constants/Motors.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkFlex;
import static com.revrobotics.CANSparkMax.IdleMode;

/*-
Expand All @@ -29,17 +30,17 @@ public interface Amper {
}

public interface Swerve {
public CANSparkMaxConfig DRIVE_CONFIG = new CANSparkMaxConfig(false, IdleMode.kBrake);
public CANSparkMaxConfig TURN_CONFIG = new CANSparkMaxConfig(false, IdleMode.kBrake);
CANSparkFlexConfig DRIVE_CONFIG = new CANSparkFlexConfig(false, IdleMode.kBrake);
CANSparkMaxConfig TURN_CONFIG = new CANSparkMaxConfig(false, IdleMode.kBrake);
}

public interface Intake {
CANSparkMaxConfig MOTOR_CONFIG = new CANSparkMaxConfig(false, IdleMode.kBrake);
}

public interface Shooter {
CANSparkMaxConfig LEFT_SHOOTER = new CANSparkMaxConfig(false,IdleMode.kCoast);
CANSparkMaxConfig RIGHT_SHOOTER = new CANSparkMaxConfig(false,IdleMode.kCoast);
CANSparkFlexConfig LEFT_SHOOTER = new CANSparkFlexConfig(false,IdleMode.kCoast);
CANSparkFlexConfig RIGHT_SHOOTER = new CANSparkFlexConfig(false,IdleMode.kCoast);
}

public interface Conveyor {
Expand Down Expand Up @@ -155,5 +156,40 @@ public void configureAsFollower(CANSparkMax motor, CANSparkMax follows) {
motor.follow(follows);
motor.burnFlash();
}
}

}

public static class CANSparkFlexConfig {
public final boolean INVERTED;
public final IdleMode IDLE_MODE;
public final int CURRENT_LIMIT_AMPS;
public final double OPEN_LOOP_RAMP_RATE;

public CANSparkFlexConfig(
boolean inverted,
IdleMode idleMode,
int currentLimitAmps,
double openLoopRampRate) {
this.INVERTED = inverted;
this.IDLE_MODE = idleMode;
this.CURRENT_LIMIT_AMPS = currentLimitAmps;
this.OPEN_LOOP_RAMP_RATE = openLoopRampRate;
}

public CANSparkFlexConfig(boolean inverted, IdleMode idleMode, int currentLimitAmps) {
this(inverted, idleMode, currentLimitAmps, 0.05);
}

public CANSparkFlexConfig(boolean inverted, IdleMode idleMode) {
this(inverted, idleMode, 80);
}

public void configure(CANSparkFlex motor) {
motor.setInverted(INVERTED);
motor.setIdleMode(IDLE_MODE);
motor.setSmartCurrentLimit(CURRENT_LIMIT_AMPS);
motor.setOpenLoopRampRate(OPEN_LOOP_RAMP_RATE);
motor.burnFlash();
}
}
}
10 changes: 5 additions & 5 deletions src/main/java/com/stuypulse/robot/subsystems/ShooterTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,19 +5,19 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkLowLevel.MotorType;

public class ShooterTest extends SubsystemBase{
private final CANSparkMax leftMotor;
private final CANSparkMax rightMotor;
private final CANSparkFlex leftMotor;
private final CANSparkFlex rightMotor;

private final RelativeEncoder leftEncoder;
private final RelativeEncoder rightEncoder;
public ShooterTest() {
leftMotor = new CANSparkMax(Ports.Shooter.LEFT_MOTOR, MotorType.kBrushless);
rightMotor = new CANSparkMax(Ports.Shooter.RIGHT_MOTOR, MotorType.kBrushless);
leftMotor = new CANSparkFlex(Ports.Shooter.LEFT_MOTOR, MotorType.kBrushless);
rightMotor = new CANSparkFlex(Ports.Shooter.RIGHT_MOTOR, MotorType.kBrushless);

leftEncoder = leftMotor.getEncoder();
rightEncoder = rightMotor.getEncoder();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,22 +1,23 @@
package com.stuypulse.robot.subsystems.swervetests.module;

import com.ctre.phoenix6.hardware.CANcoder;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkLowLevel.MotorType;


public class SwerveModuleTest {
private final CANSparkMax turnMotor;
private final CANSparkMax driveMotor;
private final CANSparkFlex driveMotor;
private final String id;

private final RelativeEncoder driveEncoder;
private final CANcoder turnEncoder;

public SwerveModuleTest(String id, int driveID, int turnID, int encoderID) {
turnMotor = new CANSparkMax(turnID, MotorType.kBrushless);
driveMotor = new CANSparkMax(driveID, MotorType.kBrushless);
driveMotor = new CANSparkFlex(driveID, MotorType.kBrushless);

driveEncoder = driveMotor.getEncoder();
turnEncoder = new CANcoder(encoderID);
Expand Down

0 comments on commit bc9e9cd

Please sign in to comment.