Skip to content

Commit

Permalink
start elevator --- carson and max c
Browse files Browse the repository at this point in the history
  • Loading branch information
Ishan1522 committed Jan 6, 2025
1 parent bc353ad commit f4d0223
Show file tree
Hide file tree
Showing 6 changed files with 34 additions and 145 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ public RobotContainer() {
}

case SIM -> {

/* Sim robot, instantiate physics sim IO implementations */

/* create simulations */
Expand Down
8 changes: 5 additions & 3 deletions src/main/java/frc/robot/subsystems/elevator/Elevator.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,14 @@
/** This subsystem is an elevator that uses PID for its position. */
// 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.elevator;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import org.littletonrobotics.junction.Logger;

public class Elevator extends SubsystemBase {
/** Creates a new Elevator. */
/** Creates a new elevator. */
private ElevatorInterface elevatorInterface;

private ElevatorInputsAutoLogged inputs = new ElevatorInputsAutoLogged();
Expand All @@ -32,7 +35,6 @@ public void setVolts(double volts) {

@Override
public void periodic() {
// This method will be called once per scheduler run
elevatorInterface.updateInputs(inputs);
Logger.processInputs("Elevator/", inputs);
}
Expand Down
25 changes: 0 additions & 25 deletions src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java

This file was deleted.

23 changes: 8 additions & 15 deletions src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java
Original file line number Diff line number Diff line change
@@ -1,28 +1,21 @@
// 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.elevator;

import org.littletonrobotics.junction.AutoLog;

public interface ElevatorInterface {

/** Creates a new ElevatorInterface. */
@AutoLog
public static class ElevatorInputs {
public double leaderMotorPosition = 0.0;

public double followerMotorPosition = 0.0;
public static class ElevatorInputs { // For values
public double rightMotorPosition = 0.0;
public double leftMotorPosition = 0.0;
}

/**
* Updates inputs for elevator for AdvantageKit to log
*
* @param inputs values related to the elevator
*/
public default void updateInputs(ElevatorInputs inputs) {}

/**
* Gets the current position of the elevator
*
* @return
*/
public default double getElevatorPosition() {
return 0.0;
}
Expand Down
66 changes: 9 additions & 57 deletions src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java
Original file line number Diff line number Diff line change
@@ -1,61 +1,13 @@
package frc.robot.subsystems.elevator;

import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.Voltage;
import frc.robot.subsystems.elevator.ElevatorInterface.ElevatorInputs;

/** Add your docs here. */
public class PhysicalElevator {
private TalonFX leaderMotor = new TalonFX(ElevatorConstants.ELEVATOR_LEADER_MOTOR_ID);
private TalonFX followerMotor = new TalonFX(ElevatorConstants.ELEVATOR_FOLLOWER_MOTOR_ID);

StatusSignal<Angle> leaderPosition;
StatusSignal<Angle> followerPosition;

StatusSignal<Voltage> leaderAppliedVoltage;
StatusSignal<Voltage> followerAppliedVoltage;

public PhysicalElevator() {
leaderPosition = leaderMotor.getRotorPosition();
followerPosition = followerMotor.getRotorPosition();

leaderAppliedVoltage = leaderMotor.getMotorVoltage();
followerAppliedVoltage = followerMotor.getMotorVoltage();
// 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.

TalonFXConfiguration elevatorConfig = new TalonFXConfiguration();

elevatorConfig.Slot0.kP = ElevatorConstants.ELEVATOR_P;
elevatorConfig.Slot0.kI = ElevatorConstants.ELEVATOR_I;
elevatorConfig.Slot0.kD = ElevatorConstants.ELEVATOR_D;

leaderMotor.getConfigurator().apply(elevatorConfig);
followerMotor.getConfigurator().apply(elevatorConfig);
}

public void updateInputs(ElevatorInputs inputs) {
inputs.leaderMotorPosition = leaderPosition.getValueAsDouble();
inputs.followerMotorPosition = followerPosition.getValueAsDouble();
}

public double getElevatorPosition() {
return leaderPosition.getValueAsDouble();
}

public void setElevatorPosition(double position) {
leaderMotor.setPosition(position);
followerMotor.setPosition(position);
}
package frc.robot.subsystems.elevator;

public void setVolts(double volts) {
leaderMotor.setVoltage(volts);
followerMotor.setVoltage(volts);
;
}
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public double getVolts() {
return leaderMotor.getMotorVoltage().getValueAsDouble();
}
public class PhysicalElevator implements ElevatorInterface {
/** Creates a new ElevatorHardware. */
public PhysicalElevator() {}

}
56 changes: 11 additions & 45 deletions src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java
Original file line number Diff line number Diff line change
@@ -1,51 +1,17 @@
package frc.robot.subsystems.elevator;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.ElevatorSim;

/** Add your docs here. */
public class SimulatedElevator implements ElevatorInterface {
private ElevatorSim elevatorSim =
new ElevatorSim(
DCMotor.getFalcon500(2),
ElevatorConstants.ELEVATOR_GEAR_RATIO,
ElevatorConstants.ELEVATOR_CARRIAGE_MASS,
ElevatorConstants.DRUM_RADIUS,
ElevatorConstants.MIN_HEIGHT,
ElevatorConstants.MAX_HEIGHT,
true,
0.0);
private PIDController simPID;
private double currentVolts;
// 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.

public SimulatedElevator() {
simPID =
new PIDController(
ElevatorConstants.ELEVATOR_P,
ElevatorConstants.ELEVATOR_I,
ElevatorConstants.ELEVATOR_D);
}

public void updateInputs(ElevatorInputs inputs) {
inputs.leaderMotorPosition = getElevatorPosition();
inputs.followerMotorPosition = getElevatorPosition();
}
package frc.robot.subsystems.elevator;

public void setElevatorPosition(double position) {
setVolts(simPID.calculate(getElevatorPosition(), position));
}
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public double getElevatorPosition() {
return elevatorSim.getPositionMeters();
}

public void setVolts(double volts) {
currentVolts = simPID.calculate(volts);
elevatorSim.setInputVoltage(currentVolts);
}
public class SimulatedElevator extends SubsystemBase {
/** Creates a new ElevatorSimulation. */
public SimulatedElevator() {}

public double getVolts() {
return currentVolts;
@Override
public void periodic() {
// This method will be called once per scheduler run
}
}

0 comments on commit f4d0223

Please sign in to comment.