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

Updated-to-4011-specs-2024 #52

Open
wants to merge 5 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
2 changes: 1 addition & 1 deletion .wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,5 @@
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2024",
"teamNumber": 364
"teamNumber": 4011
}
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1"
id "edu.wpi.first.GradleRIO" version "2024.2.1"
}

java {
Expand Down
35 changes: 20 additions & 15 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,20 @@
public final class Constants {
public static final double stickDeadband = 0.1;

public static final class Swerve {
public static final int pigeonID = 1;
public static final class Swerve {
public static final int pigeonID = 13;

public static final class ShooterConstants {
public static final double kRightShooterCMDVolts = 10.0;
public static final double kLeftShooterCMDVolts = 6.0;
}

public static final COTSTalonFXSwerveConstants chosenModule = //TODO: This must be tuned to specific robot
COTSTalonFXSwerveConstants.SDS.MK4i.Falcon500(COTSTalonFXSwerveConstants.SDS.MK4i.driveRatios.L2);
COTSTalonFXSwerveConstants.SDS.MK4i.Falcon500(COTSTalonFXSwerveConstants.SDS.MK4i.driveRatios.L3);

/* Drivetrain Constants */
public static final double trackWidth = Units.inchesToMeters(21.73); //TODO: This must be tuned to specific robot
public static final double wheelBase = Units.inchesToMeters(21.73); //TODO: This must be tuned to specific robot
public static final double trackWidth = Units.inchesToMeters(23.81); //TODO: This must be tuned to specific robot
public static final double wheelBase = Units.inchesToMeters(23.63); //TODO: This must be tuned to specific robot
public static final double wheelCircumference = chosenModule.wheelCircumference;

/* Swerve Kinematics
Expand Down Expand Up @@ -92,8 +97,8 @@ public static final class Swerve {
public static final class Mod0 { //TODO: This must be tuned to specific robot
public static final int driveMotorID = 1;
public static final int angleMotorID = 2;
public static final int canCoderID = 1;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(0.0);
public static final int canCoderID = 9;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(101.953);
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}
Expand All @@ -102,18 +107,18 @@ public static final class Mod0 { //TODO: This must be tuned to specific robot
public static final class Mod1 { //TODO: This must be tuned to specific robot
public static final int driveMotorID = 3;
public static final int angleMotorID = 4;
public static final int canCoderID = 2;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(0.0);
public static final int canCoderID = 10;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(68.379);
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}

/* Back Left Module - Module 2 */
public static final class Mod2 { //TODO: This must be tuned to specific robot
public static final int driveMotorID = 5;
public static final int driveMotorID = 5 ;
public static final int angleMotorID = 6;
public static final int canCoderID = 3;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(0.0);
public static final int canCoderID = 11;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(173.936);
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}
Expand All @@ -122,16 +127,16 @@ public static final class Mod2 { //TODO: This must be tuned to specific robot
public static final class Mod3 { //TODO: This must be tuned to specific robot
public static final int driveMotorID = 7;
public static final int angleMotorID = 8;
public static final int canCoderID = 4;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(0.0);
public static final int canCoderID = 12;
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(-3.604);
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}
}

public static final class AutoConstants { //TODO: The below constants are used in the example auto, and must be tuned to specific robot
public static final double kMaxSpeedMetersPerSecond = 3;
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
public static final double kMaxAccelerationMetersPerSecondSquared =3;
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;

Expand Down
51 changes: 44 additions & 7 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;

import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants.Swerve.ShooterConstants;
import frc.robot.autos.*;
import frc.robot.commands.*;
import frc.robot.subsystems.*;
Expand All @@ -19,16 +20,22 @@
*/
public class RobotContainer {
/* Controllers */
private final Joystick driver = new Joystick(0);
// private final Joystick driver = new Joystick(0);

private final ShooterSubsystem shooterSubsystem = new ShooterSubsystem();
private final KickerSubsystem kickerSubsystem = new KickerSubsystem();
private final XboxController driverXbox = new XboxController(0);


/* Drive Controls */
private final int translationAxis = XboxController.Axis.kLeftY.value;
private final int strafeAxis = XboxController.Axis.kLeftX.value;
private final int rotationAxis = XboxController.Axis.kRightX.value;

/* Driver Buttons */
private final JoystickButton zeroGyro = new JoystickButton(driver, XboxController.Button.kY.value);
private final JoystickButton robotCentric = new JoystickButton(driver, XboxController.Button.kLeftBumper.value);
private final JoystickButton zeroGyro = new JoystickButton(driverXbox, XboxController.Button.kY.value);
private final JoystickButton robotCentric = new JoystickButton(driverXbox, XboxController.Button.kLeftBumper.value);


/* Subsystems */
private final Swerve s_Swerve = new Swerve();
Expand All @@ -39,12 +46,14 @@ public RobotContainer() {
s_Swerve.setDefaultCommand(
new TeleopSwerve(
s_Swerve,
() -> -driver.getRawAxis(translationAxis),
() -> -driver.getRawAxis(strafeAxis),
() -> -driver.getRawAxis(rotationAxis),
() -> -driverXbox.getRawAxis(translationAxis),
() -> -driverXbox.getRawAxis(strafeAxis),
() -> -driverXbox.getRawAxis(rotationAxis),
() -> robotCentric.getAsBoolean()
)
);

shooterSubsystem.setDefaultCommand(new ShooterCommand(shooterSubsystem, 0,0));

// Configure the button bindings
configureButtonBindings();
Expand All @@ -59,8 +68,36 @@ public RobotContainer() {
private void configureButtonBindings() {
/* Driver Buttons */
zeroGyro.onTrue(new InstantCommand(() -> s_Swerve.zeroHeading()));

//new Trigger(driverXbox.getLeftTriggerAxis() > 0.5) .whileTrue(new ShooterCommand(shooterSubsytem, 10.0, 6.0 ));

// driverXbox.a().whileTrue(new ShooterCommand(shooterSubsytem , 10.0,6.0));
//new JoystickButton(driverXbox, 1).whileTrue(new ShooterCommand(shooterSubsytem, 10.0, 6.0));


new JoystickButton(driverXbox, 1).whileTrue(new ShooterCommand(shooterSubsystem, 6.0, 10.0 ));
new JoystickButton(driverXbox, 2).whileTrue(new KickerCommand(kickerSubsystem, 11.0));
/*if(new JoystickButton(driverXbox, 1).whileTrue(new ShooterCommand(shooterSubsystem, 6.0, 10.0)) != null) {
if(shooterSubsystem.getRightMotorVoltage() <= 10.0){
new KickerCommand(kickerSubsystem, 11.0);

}
}*/

}


/*public void ampShooter() {
if(driverXbox.getAButtonPressed()) {
new ShooterCommand(shooterSubsystem, 6.0, 10.0);
if(shooterSubsystem.getRightMotorVoltage() >= 10.0 ){
new KickerCommand(kickerSubsystem, 5.0);
}



}
}*/
/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,16 +35,16 @@ public SwerveModule(int moduleNumber, SwerveModuleConstants moduleConstants){
this.angleOffset = moduleConstants.angleOffset;

/* Angle Encoder Config */
angleEncoder = new CANcoder(moduleConstants.cancoderID);
angleEncoder = new CANcoder(moduleConstants.cancoderID, "canivore");
angleEncoder.getConfigurator().apply(Robot.ctreConfigs.swerveCANcoderConfig);

/* Angle Motor Config */
mAngleMotor = new TalonFX(moduleConstants.angleMotorID);
mAngleMotor = new TalonFX(moduleConstants.angleMotorID, "canivore");
mAngleMotor.getConfigurator().apply(Robot.ctreConfigs.swerveAngleFXConfig);
resetToAbsolute();

/* Drive Motor Config */
mDriveMotor = new TalonFX(moduleConstants.driveMotorID);
mDriveMotor = new TalonFX(moduleConstants.driveMotorID, "canivore");
mDriveMotor.getConfigurator().apply(Robot.ctreConfigs.swerveDriveFXConfig);
mDriveMotor.getConfigurator().setPosition(0.0);
}
Expand Down
45 changes: 45 additions & 0 deletions src/main/java/frc/robot/commands/KickerCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
// 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.wpilibj2.command.Command;
import frc.robot.subsystems.KickerSubsystem;

public class KickerCommand extends Command {
/** Creates a new KickerCommand. */
private final KickerSubsystem kickerSubsystem;
private double kickerVoltage;
public KickerCommand(KickerSubsystem kickerSubsystem, double kickerVoltage) {
// Use addRequirements() here to declare subsystem dependencies.
this.kickerSubsystem = kickerSubsystem;
this.kickerVoltage = kickerVoltage;
addRequirements(kickerSubsystem);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
System.out.println("kickerCMD started");
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
kickerSubsystem.setKickerSpeed( kickerVoltage);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
kickerSubsystem.setKickerSpeed(0);
System.out.println("kickerCMD stopped");
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
49 changes: 49 additions & 0 deletions src/main/java/frc/robot/commands/ShooterCommand.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.wpilibj2.command.Command;
import frc.robot.subsystems.ShooterSubsystem;

public class ShooterCommand extends Command {
/** Creates a new ShooterCommand. */
private final ShooterSubsystem shooterSubsytem;
private double leftVoltage;
private double rightVoltage;
// private double kickerVoltage;
public ShooterCommand(ShooterSubsystem shooterSubsytem, double leftVoltage, double rightVoltage) {
// Use addRequirements() here to declare subsystem dependencies.
this.shooterSubsytem = shooterSubsytem;
this.leftVoltage = leftVoltage;
this.rightVoltage = rightVoltage;
//this.kickerVoltage = kickerVoltage;
addRequirements(shooterSubsytem);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
System.out.println("ShooterCMD started");
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
shooterSubsytem.setShooterSpeed(leftVoltage, rightVoltage);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
shooterSubsytem.setShooterSpeed(0, 0);
System.out.println("ShooterCMD stopped");
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
34 changes: 34 additions & 0 deletions src/main/java/frc/robot/subsystems/KickerSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
// 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.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;

import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class KickerSubsystem extends SubsystemBase {
/** Creates a new KickerSubsystem. */
private static CANSparkMax kickerMotor;
public KickerSubsystem() {
// kickerMotor.restoreFactoryDefaults();
kickerMotor = new CANSparkMax(14, MotorType.kBrushless);
kickerMotor.restoreFactoryDefaults();
kickerMotor.setInverted(false);
kickerMotor.setIdleMode(IdleMode.kBrake);
kickerMotor.setSmartCurrentLimit(80);
kickerMotor.burnFlash();
}

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

public void setKickerSpeed(double kickerVoltage) {
kickerMotor.setVoltage(kickerVoltage);
}
}
Loading