Skip to content

Commit

Permalink
all subsystems base code (yet to test)
Browse files Browse the repository at this point in the history
  • Loading branch information
Mukesh-Kalikaya committed Feb 13, 2025
1 parent 405f330 commit c550ccc
Show file tree
Hide file tree
Showing 5 changed files with 267 additions and 30 deletions.
72 changes: 42 additions & 30 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,30 +40,6 @@ public static class ModuleConstants {
public static final boolean[] invertedMotors = {true, true, false, false};

}

public static class ManipulatorConstants {
public static final int elevatorMaster = 61;
public static final int elevatorSlave = 62;
public static final int intake = 51;
public static final int shooterMaster = 52;
public static final int shooterSlave = 53;
public static final int shooterIntake = 54;
public static final int wrist = 55;
public static final double kP = 0;
public static final double kI = 0;
public static final double kD = 0;
public static final double wristTolerance = 0.02;
public static final double shooterNominalAngle = 67;
public static final double intakeCurrentLimit = 7;
}

public static class Wrist {
public static final double flatWristPos = 0.18069375;
public static final double shoot_from_subwoofer = 0.04958;
public static final double handoff = 0.0421;
public static final double amp = 0.02;
public static final double passing = 0.049;
}

public static class Swerve {
public static final Double angularPercentage = -0.7;
Expand All @@ -78,13 +54,45 @@ public static class Swerve {
public static final boolean blueFlipState = false;
}

public static class DriveBaseConstants {
public static final double driveBaseRadius = (Double) 0.51 * Math.sqrt(2);
public static class ElevatorConstants {
public static final int leftSparkMax = 61;
public static final int leftCurrentLimit = 40;
public static final boolean leftInverted = false;
public static final double leftKP = 2.0;
public static final double leftKI = 0.0;
public static final double leftKD = 0.0;

public static final int rightSparkMax = 62;
public static final int rightCurrentLimit = 40;
public static final boolean rightInverted = false;
public static final double rightKP = 2.0;
public static final double rightKI = 0.0;
public static final double rightKD = 0.0;
}

public static class IntakeConstants {
public static final int wristSparkMax = 58;
public static final int wristCurrentLimit = 40;
public static final boolean wristInverted = false;
public static final double wristKP = 2.0;
public static final double wristKI = 0.0;
public static final double wristKD = 0.0;

public static final int spinnerSparkMax = 59;
public static final int spinnerCurrentLimit = 40;
public static final boolean spinnerInverted = false;
}

public static class SampleConstants {
public static final int sampleNeo = 15;
public static final int sampleFlex = 59;
public static class PassageConstants {
public static final int spinnerSparkMax = 60;
public static final int spinnerCurrentLimit = 40;
public static final boolean spinnerInverted = false;
}

public static class OuttakeConstants {
public static final int spinnerSparkMax = 57;
public static final int spinnerCurrentLimit = 40;
public static final boolean spinnerInverted = false;
}

public static class Auton {
Expand Down Expand Up @@ -138,5 +146,9 @@ public static class FieldConstants {

public static final Pose2d blueCenterNotePose = new Pose2d(3.5, 5.5, new Rotation2d());
public static final Pose2d redCenterNotePose = new Pose2d(14.5, 5.5, Rotation2d.fromDegrees(-180));
}
}

public static class DriveBaseConstants {
public static final double driveBaseRadius = (Double) 0.51 * Math.sqrt(2);
}
}
72 changes: 72 additions & 0 deletions src/main/java/frc/robot/subsystems/Elevator.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
// 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.spark.ClosedLoopSlot;
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.ControlType;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class Elevator extends SubsystemBase {
private final SparkMax leftMotor;
private final SparkMax rightMotor;

private final SparkMaxConfig leftMotorConfig;
private final SparkMaxConfig rightMotorConfig;

private SparkClosedLoopController leftController;
private SparkClosedLoopController rightController;

/** Creates a new Elevator. */
public Elevator() {
leftMotor = new SparkMax(Constants.ElevatorConstants.leftSparkMax, SparkMax.MotorType.kBrushless);
leftMotorConfig = new SparkMaxConfig();

leftMotorConfig
.inverted(Constants.ElevatorConstants.leftInverted)
.smartCurrentLimit(Constants.ElevatorConstants.leftCurrentLimit)
.idleMode(IdleMode.kBrake)
.encoder.positionConversionFactor(1/12);

leftMotorConfig.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
.outputRange(-1, 1)
.pid(Constants.ElevatorConstants.leftKP, Constants.ElevatorConstants.leftKI, Constants.ElevatorConstants.leftKD);

leftController = leftMotor.getClosedLoopController();

rightMotor = new SparkMax(Constants.ElevatorConstants.rightSparkMax, SparkMax.MotorType.kBrushless);
rightMotorConfig = new SparkMaxConfig();

rightMotorConfig
.inverted(Constants.ElevatorConstants.rightInverted)
.smartCurrentLimit(Constants.ElevatorConstants.rightCurrentLimit)
.idleMode(IdleMode.kBrake)
.encoder.positionConversionFactor(1/12);

rightMotorConfig.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
.outputRange(-1, 1)
.pid(Constants.ElevatorConstants.rightKP, Constants.ElevatorConstants.rightKI, Constants.ElevatorConstants.rightKD);

rightController = rightMotor.getClosedLoopController();
}

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

public void setElevatorPosition(double position) {
leftController.setReference(position, ControlType.kPosition, ClosedLoopSlot.kSlot0);
rightController.setReference(position, ControlType.kPosition, ClosedLoopSlot.kSlot0);
}
}
71 changes: 71 additions & 0 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
// 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.spark.ClosedLoopSlot;
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.ControlType;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class Intake extends SubsystemBase {
private final SparkMax wristMotor;
private final SparkMax spinnerMotor;

private final SparkMaxConfig wristConfig;
private final SparkMaxConfig spinnerConfig;

private SparkClosedLoopController wristController;

/** Creates a new Intake. */
public Intake() {
wristMotor = new SparkMax(Constants.IntakeConstants.wristSparkMax, MotorType.kBrushless);
wristConfig = new SparkMaxConfig();

wristConfig
.inverted(Constants.IntakeConstants.wristInverted)
.smartCurrentLimit(Constants.IntakeConstants.wristCurrentLimit)
.idleMode(IdleMode.kBrake)
.encoder.positionConversionFactor(1/12);

wristConfig.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
.outputRange(-1, 1)
.pid(Constants.IntakeConstants.wristKP, Constants.IntakeConstants.wristKI, Constants.IntakeConstants.wristKD);

wristMotor.configure(wristConfig, ResetMode.kResetSafeParameters, null);
wristController = wristMotor.getClosedLoopController();

spinnerMotor = new SparkMax(Constants.IntakeConstants.spinnerSparkMax, MotorType.kBrushless);
spinnerConfig = new SparkMaxConfig();

spinnerConfig
.inverted(Constants.IntakeConstants.spinnerInverted)
.smartCurrentLimit(Constants.IntakeConstants.spinnerCurrentLimit)
.idleMode(IdleMode.kBrake);

spinnerMotor.configure(spinnerConfig, ResetMode.kResetSafeParameters, null);
}

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

public void setWristPosition(double position) {
wristController.setReference(position, ControlType.kPosition, ClosedLoopSlot.kSlot0);
}

public void setSpinnerPower(double power) {
spinnerMotor.set(power);
}
}
41 changes: 41 additions & 0 deletions src/main/java/frc/robot/subsystems/Outtake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// 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.spark.SparkMax;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class Outtake extends SubsystemBase {
private final SparkMax spinnerMotor;

private final SparkMaxConfig spinnerConfig;
/** Creates a new Outtake. */
public Outtake() {
spinnerMotor = new SparkMax(Constants.OuttakeConstants.spinnerSparkMax, MotorType.kBrushless);
spinnerConfig = new SparkMaxConfig();

spinnerConfig
.inverted(Constants.OuttakeConstants.spinnerInverted)
.smartCurrentLimit(Constants.OuttakeConstants.spinnerCurrentLimit)
.idleMode(IdleMode.kBrake);

spinnerMotor.configure(spinnerConfig, ResetMode.kResetSafeParameters, null);
}

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

public void setOuttakeSpeed(double speed) {
spinnerMotor.set(speed);
}
}
41 changes: 41 additions & 0 deletions src/main/java/frc/robot/subsystems/Passage.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// 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.spark.SparkMax;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class Passage extends SubsystemBase {
private final SparkMax spinnerMotor;

private final SparkMaxConfig spinnerConfig;

/** Creates a new Passage. */
public Passage() {
spinnerMotor = new SparkMax(Constants.PassageConstants.spinnerSparkMax, SparkMax.MotorType.kBrushless);
spinnerConfig = new SparkMaxConfig();

spinnerConfig
.inverted(Constants.PassageConstants.spinnerInverted)
.smartCurrentLimit(Constants.PassageConstants.spinnerCurrentLimit)
.idleMode(IdleMode.kCoast);

spinnerMotor.configure(spinnerConfig, ResetMode.kResetSafeParameters, null);
}

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

public void setSpinnerSpeed(double speed) {
spinnerMotor.set(speed);
}
}

0 comments on commit c550ccc

Please sign in to comment.