Skip to content

Commit

Permalink
WORKING OFFSETS AHHHHH
Browse files Browse the repository at this point in the history
  • Loading branch information
LTeixeira4909 committed Jan 18, 2025
1 parent b8e6ad8 commit c76b7f8
Show file tree
Hide file tree
Showing 9 changed files with 589 additions and 482 deletions.
7 changes: 7 additions & 0 deletions .vscode/launch.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,13 @@
{
"version": "0.2.0",
"configurations": [
{
"type": "java",
"name": "Main",
"request": "launch",
"mainClass": "frc.robot.Main",
"projectName": "2025-Reefscape"
},
{
"type": "wpilib",
"name": "WPILib Desktop Debug",
Expand Down
13 changes: 11 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,12 @@ public RobotContainer() {
s_Elevator = new Elevator(new ElevatorIOTalonFX());
configureBindings();
}



public void periodic() {
System.out.println("Elevator Command"+s_Elevator.getCurrentCommand());
}
private void configureBindings() {
// Note that X is defined as forward according to WPILib convention,
// and Y is defined as to the left according to WPILib convention.
Expand All @@ -77,11 +82,15 @@ private void configureBindings() {
// point.withModuleDirection(
// new Rotation2d(-joystick.getLeftY(), -joystick.getLeftX()))));

joystick.x().whileTrue(s_Shooter.shootL2()).onFalse(s_Shooter.stop());
joystick.rightTrigger().whileTrue(s_Shooter.shootL2()).onFalse(s_Shooter.stop());
joystick.y().whileTrue(s_Shooter.intake()).onFalse(s_Shooter.stop());
joystick.a().whileTrue(s_Shooter.shootTrough()).onFalse(s_Shooter.stop());
joystick.b().whileTrue(s_Elevator.goToL1()).onFalse(s_Elevator.stop());

joystick.b().onTrue(s_Elevator.goToL1()).onFalse(s_Elevator.stop());
joystick.leftBumper().onTrue(s_Elevator.goToL2
()).onFalse(s_Elevator.stop());
joystick.rightBumper().onTrue(s_Elevator.goToL3()).onFalse(s_Elevator.stop());
joystick.leftTrigger().onTrue(s_Elevator.goToL4()).onFalse(s_Elevator.stop());
joystick.povUp().whileTrue(s_Elevator.moveUp()).onFalse(s_Elevator.stop());
joystick.povDown().whileTrue(s_Elevator.moveDown()).onFalse(s_Elevator.stop());

Expand Down
60 changes: 47 additions & 13 deletions src/main/java/frc/robot/subsystems/elevator/Elevator.java
Original file line number Diff line number Diff line change
@@ -1,40 +1,74 @@
package frc.robot.subsystems.elevator;

import edu.wpi.first.networktables.DoublePublisher;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Elevator extends SubsystemBase {
private final ElevatorIO m_io;
private final double L1Setpoint = 100;
private final double L2Setpoint = 5;
private final double L3Setpoint = 0;
private final double L4Setpoint = 0;
private final NetworkTableInstance inst = NetworkTableInstance.getDefault();
private final NetworkTable elevatorTable = inst.getTable("Elevator");
private final DoublePublisher motorValPub= elevatorTable.getDoubleTopic("Motor Val").publish();
private final DoublePublisher motorVolPub= elevatorTable.getDoubleTopic("Motor Vol").publish();
private final DoublePublisher rotPub= elevatorTable.getDoubleTopic("Rotations").publish();
private final DoublePublisher setPub= elevatorTable.getDoubleTopic("Setpoint").publish();

final double m_gearRatio = 5/1 * 5/1 * 48/72;
private final ElevatorIO m_io;
private final double L1Setpoint = 29;
private final double L2Setpoint = 32.5;
private final double L3Setpoint = 51.5;
private final double L4Setpoint = 76;
//inch to rotations of the motor
final double m_gearRatio = 0.5 * (1d / (1.75100 * Math.PI)) * ( 2d / 3d ) * 25;

public Elevator(ElevatorIO io) {
m_io = io;

}

public Command moveUp() {
return this.run(() -> m_io.setVoltage(1));
return this.runOnce(() -> m_io.setVoltage(3)).withName("UP");
}

public Command stop() {
return this.run(() -> m_io.setVoltage(0));
return this.runOnce(() -> m_io.setVoltage(0)).withName("Stop");
}

public Command moveDown() {
return this.run(() -> m_io.setVoltage(-1));
return this.runOnce(() -> m_io.setVoltage(-3)).withName("Move Down");
}

public Command goToL1(){
// return this.run(() -> m_io.gotosetpoint(L1Setpoint,m_gearRatio));
return this.run(() -> {
// System.out.println("L1");
return this.runOnce(() -> {
m_io.gotosetpoint(L1Setpoint, m_gearRatio);
});
}).withName("L1");
}
public Command goToL2(){
// return this.run(() -> m_io.gotosetpoint(L1Setpoint,m_gearRatio));
return this.runOnce(() -> {
m_io.gotosetpoint(L2Setpoint, m_gearRatio);
}).withName("L2");
}
public Command goToL3(){
// return this.run(() -> m_io.gotosetpoint(L1Setpoint,m_gearRatio));
return this.runOnce(() -> {
m_io.gotosetpoint(L3Setpoint, m_gearRatio);
}).withName("L3");
}
public Command goToL4(){
// return this.run(() -> m_io.gotosetpoint(L1Setpoint,m_gearRatio));
return this.runOnce(() -> {
m_io.gotosetpoint(L4Setpoint, m_gearRatio);
}).withName("L4");
}
@Override
public void periodic() {
super.periodic();
motorValPub.set(m_io.getVelocity());
motorVolPub.set(m_io.getVoltage());
setPub.set(m_io.getSetpoint());
rotPub.set(m_io.getPosition());
}

}
16 changes: 14 additions & 2 deletions src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,13 @@
package frc.robot.subsystems.elevator;

import org.littletonrobotics.junction.AutoLog;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;

public interface ElevatorIO {


@AutoLog
public static class ElevatorIOInputs {
public double voltage = 0d;
}
Expand All @@ -12,5 +16,13 @@ public default void setVoltage(double voltage) {}

public default void setBrakeMode(boolean enableBrakeMode) {}

public abstract Command gotosetpoint(double setpoint, double gearRatio);
public default void gotosetpoint(double setpoint, double gearRatio) {}

public default double getVelocity() { return 0; }

public default double getVoltage() { return 0; }

public default double getPosition() { return 0; }

public default double getSetpoint() { return 0; }
}
91 changes: 53 additions & 38 deletions src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java
Original file line number Diff line number Diff line change
@@ -1,61 +1,71 @@
package frc.robot.subsystems.elevator;

import com.ctre.phoenix6.configs.MotorOutputConfigs;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.Follower;
import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;

import edu.wpi.first.networktables.DoubleArrayPublisher;
import edu.wpi.first.networktables.DoublePublisher;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class ElevatorIOTalonFX extends SubsystemBase implements ElevatorIO{




private final TalonFX m_left;
private final TalonFX m_right;
final PositionVoltage m_request = new PositionVoltage(0).withSlot(0);
private double m_rotations;
final PositionVoltage m_request;
//final VelocityVoltage m_request = new VelocityVoltage(0).withSlot(0);
//private final PositionVoltage m_request;

public ElevatorIOTalonFX() {




m_left = new TalonFX(21, "CANivore2");
m_right = new TalonFX(22, "CANivore2");


m_request = new PositionVoltage(0).withSlot(0);

final TalonFXConfiguration elevatorMotorConfig = new TalonFXConfiguration();
final MotorOutputConfigs outputConfigs = new MotorOutputConfigs();
outputConfigs.Inverted = InvertedValue.Clockwise_Positive;
elevatorMotorConfig.CurrentLimits.SupplyCurrentLimit = 40.0;
elevatorMotorConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
// in init function, set slot 0 gains
var slot0Configs = new Slot0Configs();
slot0Configs.kP = 2.4; // An error of 1 rotation results in 2.4 V output
slot0Configs.kP = 1; // An error of 1 rotation results in 2.4 V output
slot0Configs.kI = 0; // no output for integrated error
slot0Configs.kD = 1; // A velocity of 1 rps results in 0.1 V output
m_left.setControl(new Follower(22, false));

m_right.setPosition(0);
// create a position closed-loop request, voltage output, slot 0 configs
//m_request = new PositionVoltage(0).withSlot(0);
//

// set position to 10 rotations

m_left.getConfigurator().apply(slot0Configs);
m_right.getConfigurator().apply(slot0Configs);

slot0Configs.kD = 0; // A velocity of 1 rps results in 0.1 V output
slot0Configs.kG = 0;;

m_right.setPosition(29 * (0.5 * (1d / (1.75100 * Math.PI)) * ( 2d / 3d ) * 25));
m_left.getConfigurator().apply(elevatorMotorConfig);
m_right.getConfigurator().apply(elevatorMotorConfig);
m_right.getConfigurator().apply(outputConfigs);
m_left.getConfigurator().apply(slot0Configs);
m_right.getConfigurator().apply(slot0Configs);
m_left.setControl(new Follower(22, true));
}

public void setVoltage(double voltage) {
final VoltageOut m_request = new VoltageOut(0);

m_left.setControl(m_request.withOutput(-voltage));
m_right.setControl(m_request.withOutput(voltage));
// return this.runOnce(()->{
final VoltageOut request = new VoltageOut(0);
m_left.setControl(request.withOutput(-voltage));
m_right.setControl(request.withOutput(voltage));
// });
System.out.println("volts:" + m_right.getMotorVoltage());
}

Expand All @@ -65,23 +75,28 @@ public void setBrakeMode(boolean enableBrakeMode) {
m_left.setNeutralMode(neutralModeValue);
m_right.setNeutralMode(neutralModeValue);
}
@Override
public void gotosetpoint(double setpoint, double gearRatio) {
double rotations = setpoint * gearRatio;
m_rotations = rotations;
System.out.println("rotations:" + rotations);
m_right.setControl(m_request.withPosition(rotations));

public Command gotosetpoint(double setpoint, double m_gearRatio) {
return this.run(() -> {
Double rotations = setpoint + (m_gearRatio * 2 * Math.PI * 1.76/2);
m_left.setControl(m_request.withPosition(rotations));
m_right.setControl(m_request.withPosition(rotations));
System.out.println("POS:" + m_right.getPosition().toString());
System.out.println("volts:" + m_right.getMotorVoltage());
});
//
// System.out.println("setpoint: " + setpoint);
// m_left.setControl(m_request.withPosition(10));
// m_right.setControl(m_request.withPosition(10));
// System.out.println("POS:" + m_right.getPosition().toString());
// System.out.println("volts:" + m_right.getMotorVoltage()
// .toString());
}


public double getVelocity(){
return m_right.getVelocity().getValueAsDouble();
}
public double getVoltage(){
return m_right.getMotorVoltage().getValueAsDouble();
}
@Override
public double getPosition() {
return m_right.getPosition().getValueAsDouble();
}

public double getSetpoint(){
return m_rotations;
}

}
38 changes: 0 additions & 38 deletions vendordeps/PathplannerLib-2025.1.1.json

This file was deleted.

38 changes: 38 additions & 0 deletions vendordeps/PathplannerLib-2025.2.1.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
{
"fileName": "PathplannerLib-2025.2.1.json",
"name": "PathplannerLib",
"version": "2025.2.1",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2025",
"mavenUrls": [
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
],
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
"javaDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2025.2.1"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2025.2.1",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal",
"linuxathena",
"linuxarm32",
"linuxarm64"
]
}
]
}
Loading

0 comments on commit c76b7f8

Please sign in to comment.