Skip to content

Commit

Permalink
basic hang
Browse files Browse the repository at this point in the history
  • Loading branch information
rgodha24 committed Feb 26, 2024
1 parent fd7d5f9 commit d46d5c8
Show file tree
Hide file tree
Showing 7 changed files with 126 additions and 3 deletions.
4 changes: 2 additions & 2 deletions .factorypath
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<factorypath>
<factorypathentry kind="EXTJAR" id="C:\Users\Broncobotics\.gradle\caches\modules-2\files-2.1\com.squareup\javapoet\1.13.0\d6562d385049f35eb50403fa86bb11cce76b866a\javapoet-1.13.0.jar" enabled="true" runInBatchMode="false"/>
<factorypathentry kind="EXTJAR" id="C:\Users\Broncobotics\.gradle\caches\modules-2\files-2.1\org.littletonrobotics.akit.junction\junction-autolog\3.1.0\abaf89ad1ac7acc95dbc0d3f0785a39acf98dd0e\junction-autolog-3.1.0.jar" enabled="true" runInBatchMode="false"/>
<factorypathentry kind="EXTJAR" id="/Users/rohangodha/.gradle/caches/modules-2/files-2.1/org.littletonrobotics.akit.junction/junction-autolog/3.1.0/abaf89ad1ac7acc95dbc0d3f0785a39acf98dd0e/junction-autolog-3.1.0.jar" enabled="true" runInBatchMode="false"/>
<factorypathentry kind="EXTJAR" id="/Users/rohangodha/.gradle/caches/modules-2/files-2.1/com.squareup/javapoet/1.13.0/d6562d385049f35eb50403fa86bb11cce76b866a/javapoet-1.13.0.jar" enabled="true" runInBatchMode="false"/>
</factorypath>
6 changes: 5 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ public static class IntakeConstants {
public static class PivotConstants {
public static final int pivotCANId = 13;

// 80 falcon rotations = 1 pivot rotation
// 5:1 planetary + 5:1 planetary + 48:21 chain
public static final double pivotGearRatio = 57.1429;

Expand All @@ -76,4 +75,9 @@ public static class ShooterConstants {
public static final double shootingPower = -0.75;
public static final double conveyorPower = 0.6;
}

public static class HangConstants {
public static final int leaderCANId = 14;
public static final int followerCANId = 15;
}
}
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
import frc.robot.commands.FeedForwardCharacterization;
import frc.robot.commands.PivotCommands;
import frc.robot.subsystems.drive.*;
import frc.robot.subsystems.hang.*;
import frc.robot.subsystems.intake.*;
import frc.robot.subsystems.limelight.*;
import frc.robot.subsystems.pivot.*;
Expand All @@ -43,6 +44,7 @@ public class RobotContainer {
private final Pivot pivot;
private final Shooter shooter;
private final Limelight limelight;
private final Hang hang;

// Controller
private final GenericHID driver = new GenericHID(0); // hotas
Expand All @@ -67,6 +69,7 @@ public RobotContainer() {
pivot = new Pivot(new PivotIOReal());
shooter = new Shooter(new ShooterIOReal());
limelight = new Limelight(new LimelightIOReal(), drive);
hang = new Hang(new HangIOReal());


break;
Expand All @@ -85,6 +88,7 @@ public RobotContainer() {
pivot = new Pivot(new PivotIOSim());
shooter = new Shooter(new ShooterIOSim());
limelight = new Limelight(new LimelightIO() {}, drive);
hang = new Hang(new HangIOSim());

break;

Expand All @@ -102,6 +106,7 @@ public RobotContainer() {
pivot = new Pivot(new PivotIO() {});
shooter = new Shooter(new ShooterIO() {});
limelight = new Limelight(new LimelightIO() {}, drive);
hang = new Hang(new HangIO() {});

break;
}
Expand Down Expand Up @@ -146,6 +151,9 @@ private void configureButtonBindings() {
pivot.setDefaultCommand(
PivotCommands.basicOperatorControl(
pivot, () -> operator.getRightX() - operator.getLeftX()));

hang.setDefaultCommand(hang.operatorControl(() ->
operator.getRightTriggerAxis() - operator.getLeftTriggerAxis()));
}

/**
Expand Down
35 changes: 35 additions & 0 deletions src/main/java/frc/robot/subsystems/hang/Hang.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
package frc.robot.subsystems.hang;

import java.util.function.DoubleSupplier;

import org.littletonrobotics.junction.Logger;

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

public class Hang extends SubsystemBase {
HangIO io;
HangIOInputsAutoLogged inputs = new HangIOInputsAutoLogged();

public Hang(HangIO io) {
this.io = io;
}

@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Hang", inputs);
}

public void setSpeed(double speed) {
io.setSpeed(speed);
}

public Command operatorControl(DoubleSupplier speedSupplier) {
return Commands.run(() -> {
double speed = speedSupplier.getAsDouble();
setSpeed(speed * 0.1);
}, this);
}
}
15 changes: 15 additions & 0 deletions src/main/java/frc/robot/subsystems/hang/HangIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
package frc.robot.subsystems.hang;

import org.littletonrobotics.junction.AutoLog;

public interface HangIO {
@AutoLog
public static class HangIOInputs {
public double mainCurrent = 0.0;
public double followerCurrent = 0.0;
}

default void updateInputs(HangIOInputs inputs) {}

default void setSpeed(double power) {}
}
56 changes: 56 additions & 0 deletions src/main/java/frc/robot/subsystems/hang/HangIOReal.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
package frc.robot.subsystems.hang;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.Follower;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;

import frc.robot.Constants.HangConstants;

public class HangIOReal implements HangIO {

TalonFX leader;
TalonFX follower;

StatusSignal<Double> leaderCurrent;
StatusSignal<Double> followerCurrent;

public HangIOReal() {

leader = new TalonFX(HangConstants.leaderCANId);
follower = new TalonFX(HangConstants.followerCANId);

// TODO: should this boolean be false?? do they rotate in the same ways??
follower.setControl(new Follower(HangConstants.leaderCANId, true));

var config = new TalonFXConfiguration();

config.CurrentLimits.SupplyCurrentLimit = 40;
config.CurrentLimits.SupplyCurrentLimitEnable = true; config.MotorOutput.NeutralMode = NeutralModeValue.Brake;

leader.getConfigurator().apply(config);
follower.getConfigurator().apply(config);

leaderCurrent = leader.getTorqueCurrent();
followerCurrent = follower.getTorqueCurrent();

// don't really need this to update that often b/c it's just for data visualization
BaseStatusSignal.setUpdateFrequencyForAll(100.0, leaderCurrent, followerCurrent);
leader.optimizeBusUtilization(1.0);
follower.optimizeBusUtilization(1.0);

}

public void updateInputs(HangIOInputs inputs) {
inputs.mainCurrent = leaderCurrent.getValueAsDouble();
inputs.followerCurrent = followerCurrent.getValueAsDouble();
}

public void setSpeed(double power) {
leader.set(power);
}


}
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/subsystems/hang/HangIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
package frc.robot.subsystems.hang;

public class HangIOSim implements HangIO {
// todo
}

0 comments on commit d46d5c8

Please sign in to comment.