Skip to content

Commit

Permalink
Added sensors to shooter
Browse files Browse the repository at this point in the history
  • Loading branch information
danjburke12 committed Jan 27, 2024
1 parent 77b28a4 commit d237174
Show file tree
Hide file tree
Showing 10 changed files with 258 additions and 59 deletions.
8 changes: 6 additions & 2 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,11 @@
{
"name": "WPIlibUnitTests",
"workingDirectory": "${workspaceFolder}/build/jni/release",
"vmargs": [ "-Djava.library.path=${workspaceFolder}/build/jni/release" ],
"vmargs": [
"-Djava.library.path=${workspaceFolder}/build/jni/release"
],
"env": {
"LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" ,
"LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release",
"DYLD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release"
}
},
Expand Down Expand Up @@ -50,6 +52,7 @@
"cSpell.words": [
"Brushless",
"Deadband",
"digitalinputs",
"dtheta",
"Holonomic",
"Odometry",
Expand All @@ -58,6 +61,7 @@
"Setpoints",
"teleop",
"Uncomitted",
"wpilibj",
"WPILOG"
]
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
package com.team1701.lib.drivers.digitalinputs;

import org.littletonrobotics.junction.AutoLog;

public interface DigitalIO {
@AutoLog
public static class DigitalInputs {
public boolean blocked;
}

public default void updateInputs(DigitalInputs inputs) {}

public default void getBlocked() {}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
package com.team1701.lib.drivers.digitalinputs;

import edu.wpi.first.wpilibj.DigitalInput;

public class DigitalIOSensor implements DigitalIO {
private final DigitalInput mSensor;

public DigitalIOSensor(int channel) {
mSensor = new DigitalInput(channel);
}

@Override
public void updateInputs(DigitalInputs inputs) {
inputs.blocked = mSensor.get();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
package com.team1701.lib.drivers.digitalinputs;

import java.util.function.Supplier;

public class DigitalIOSim implements DigitalIO {
private final Supplier<Boolean> mBlockedSupplier;

public DigitalIOSim(Supplier<Boolean> blockedSupplier) {
mBlockedSupplier = blockedSupplier;
}

@Override
public void updateInputs(DigitalInputs inputs) {
inputs.blocked = mBlockedSupplier.get();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package com.team1701.lib.drivers.encoders;

import com.team1701.robot.Constants;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.DutyCycleEncoder;

public class EncoderIODigital implements EncoderIO {
private final DutyCycleEncoder mEncoder;

public EncoderIODigital(int channel) {
mEncoder = new DutyCycleEncoder(Constants.Shooter.kShooterThroughBoreEncoderId);
mEncoder.setDistancePerRotation(Constants.Shooter.kThroughBoreEncoderDistancePerRotation);
}

@Override
public void updateInputs(EncoderInputs inputs) {
var rotations = mEncoder.get();
inputs.position = Rotation2d.fromRotations(
rotations == Double.NaN || rotations == Double.POSITIVE_INFINITY ? 0.0 : rotations);
}

public void setPositionOffset(Rotation2d offset) {
mEncoder.setPositionOffset(MathUtil.inputModulus(offset.getRotations(), 0.0, 1.0));
}

public void setDistancePerRotation(double distancePerRotation) {
mEncoder.setDistancePerRotation(distancePerRotation);
}
}
41 changes: 30 additions & 11 deletions src/main/java/com/team1701/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -156,27 +156,46 @@ public static final class Shooter {
// TODO: Update values
public static final double kShooterReduction = 1;
public static final int kShooterUpperRollerMotorId = 0;
public static final int kShooterLowerRollerMotorId = 0;
public static final int kShooterRotationMotorId = 0;
public static final int kShooterLowerRollerMotorId = 1;
public static final int kShooterRotationMotorId = 2;

public static final double kShooterAxisHeight = Units.inchesToMeters(10);
public static final double kShooterAxisOffset = Units.inchesToMeters(10); // + is toward front of bot

public static final LoggedTunableNumber kShooterKff = new LoggedTunableNumber("Shooter/Motor/Kff");
public static final LoggedTunableNumber kShooterKp = new LoggedTunableNumber("Shooter/Motor/Kp");
public static final LoggedTunableNumber kShooterKd = new LoggedTunableNumber("Shooter/Motor/Kd");
public static final LoggedTunableNumber kRollerKff = new LoggedTunableNumber("Shooter/Motor/Roller/Kff");
public static final LoggedTunableNumber kRollerKp = new LoggedTunableNumber("Shooter/Motor/Roller/Kp");
public static final LoggedTunableNumber kRollerKd = new LoggedTunableNumber("Shooter/Motor/Roller/Kd");

public static final LoggedTunableNumber kRotationKff = new LoggedTunableNumber("Shooter/Motor/Rotation/Kff");
public static final LoggedTunableNumber kRotationKp = new LoggedTunableNumber("Shooter/Motor/Rotation/Kp");
public static final LoggedTunableNumber kRotationKd = new LoggedTunableNumber("Shooter/Motor/Rotation/Kd");

public static int kShooterEntranceSensorId;
public static int kShooterExitSensorId;
public static int kShooterThroughBoreEncoderId;

public static double kThroughBoreEncoderDistancePerRotation;

static {
switch (Configuration.getRobot()) {
case COMPETITION_BOT:
kShooterKd.initDefault(1);
kShooterKp.initDefault(0.6);
kShooterKff.initDefault(0);
kRollerKd.initDefault(1);
kRollerKp.initDefault(0.6);
kRollerKff.initDefault(0);

kRotationKd.initDefault(1);
kRotationKp.initDefault(0.6);
kRotationKff.initDefault(0);

break;
case SIMULATION_BOT:
kShooterKd.initDefault(1);
kShooterKp.initDefault(0.6);
kShooterKff.initDefault(0);
kRollerKd.initDefault(1);
kRollerKp.initDefault(0.6);
kRollerKff.initDefault(0);

kRotationKd.initDefault(1);
kRotationKp.initDefault(0.6);
kRotationKff.initDefault(0);
break;
default:
throw new UnsupportedOperationException("No shooter configuration for " + Configuration.getRobot());
Expand Down
56 changes: 43 additions & 13 deletions src/main/java/com/team1701/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,15 @@
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.util.PathPlannerLogging;
import com.team1701.lib.alerts.TriggeredAlert;
import com.team1701.lib.drivers.digitalinputs.DigitalIOSensor;
import com.team1701.lib.drivers.encoders.EncoderIO;
import com.team1701.lib.drivers.encoders.EncoderIOAnalog;
import com.team1701.lib.drivers.gyros.GyroIO;
import com.team1701.lib.drivers.gyros.GyroIOPigeon2;
import com.team1701.lib.drivers.gyros.GyroIOSim;
import com.team1701.lib.drivers.motors.MotorIO;
import com.team1701.lib.util.GeometryUtil;
import com.team1701.lib.util.LoggedTunableNumber;
import com.team1701.robot.Configuration.Mode;
import com.team1701.robot.commands.AutonomousCommands;
import com.team1701.robot.estimation.PoseEstimator;
Expand All @@ -25,14 +27,18 @@
import com.team1701.robot.subsystems.drive.SwerveModule.SwerveModuleIO;
import com.team1701.robot.subsystems.shooter.Shooter;
import com.team1701.robot.subsystems.shooter.ShooterMotorFactory;
import com.team1701.robot.subsystems.shooter.ShooterMotorFactory.ShooterMotorUsage;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardBoolean;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

import static com.team1701.robot.commands.DriveCommands.*;
Expand All @@ -44,6 +50,7 @@ public class RobotContainer {
// public final Vision mVision;

private final CommandXboxController mDriverController = new CommandXboxController(0);
// Trigger bButton = mDriverController.b();
private final LoggedDashboardChooser<Command> autonomousModeChooser = new LoggedDashboardChooser<>("Auto Mode");
private final boolean kAllianceIsBlue;

Expand Down Expand Up @@ -76,14 +83,17 @@ public RobotContainer() {
new EncoderIOAnalog(2)),
}));

// TODO: update ID
// TODO: update IDs
shooter = Optional.of(new Shooter(
ShooterMotorFactory.createDriveMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId),
ShooterMotorFactory.createDriveMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId),
ShooterMotorFactory.createDriveMotorIOSparkFlex(
Constants.Shooter.kShooterRotationMotorId)));
ShooterMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterRotationMotorId, ShooterMotorUsage.ROTATION),
new DigitalIOSensor(Constants.Shooter.kShooterEntranceSensorId),
new DigitalIOSensor(Constants.Shooter.kShooterExitSensorId),
new EncoderIOAnalog(Constants.Shooter.kShooterThroughBoreEncoderId)));
break;
case SIMULATION_BOT:
kAllianceIsBlue = true;
Expand All @@ -99,9 +109,16 @@ public RobotContainer() {

drive = Optional.of(simDrive);
shooter = Optional.of(new Shooter(
Shooter.createSim(DCMotor.getNeoVortex(1)),
Shooter.createSim(DCMotor.getNeoVortex(1)),
Shooter.createSim(DCMotor.getNeoVortex(1))));
Shooter.createMotorSim(DCMotor.getNeoVortex(1)),
Shooter.createMotorSim(DCMotor.getNeoVortex(1)),
Shooter.createMotorSim(DCMotor.getNeoVortex(1)),
Shooter.createDigitalSim(() ->
new LoggedDashboardBoolean("SimulatedShooter/EntranceSensorBlocked", false).get()),
Shooter.createDigitalSim(() ->
new LoggedDashboardBoolean("SimulatedShooter/ExitSensorBlocked", false).get()),
Shooter.createEncoderSim(() -> new Rotation2d(Units.degreesToRadians(
new LoggedTunableNumber("SimulatedThroughBoreEncoder/InitialAngleDegrees", 30)
.get())))));
break;
default:
kAllianceIsBlue = true;
Expand Down Expand Up @@ -130,9 +147,15 @@ public RobotContainer() {
new AprilTagCameraIO() {})); */

this.mShooter = shooter.orElseGet(() -> new Shooter(
ShooterMotorFactory.createDriveMotorIOSparkFlex(Constants.Shooter.kShooterUpperRollerMotorId),
ShooterMotorFactory.createDriveMotorIOSparkFlex(Constants.Shooter.kShooterUpperRollerMotorId),
ShooterMotorFactory.createDriveMotorIOSparkFlex(Constants.Shooter.kShooterRotationMotorId)));
ShooterMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterUpperRollerMotorId, ShooterMotorUsage.ROLLER),
ShooterMotorFactory.createShooterMotorIOSparkFlex(
Constants.Shooter.kShooterRotationMotorId, ShooterMotorUsage.ROTATION),
new DigitalIOSensor(Constants.Shooter.kShooterEntranceSensorId),
new DigitalIOSensor(Constants.Shooter.kShooterExitSensorId),
new EncoderIOAnalog(Constants.Shooter.kShooterThroughBoreEncoderId)));

setupControllerBindings();
setupAutonomous();
Expand All @@ -155,6 +178,13 @@ private void setupControllerBindings() {
() -> mDriverController.rightTrigger().getAsBoolean()
? Constants.Drive.kSlowKinematicLimits
: Constants.Drive.kFastKinematicLimits));
/* mDriverController
.b()
.onTrue(runOnce(
() -> DriveCommands.rotateRelativeToRobot(
mDrive, new Rotation2d(2.5), Constants.Drive.kFastKinematicLimits, true),
mDrive));
TriggeredAlert.info("Driver B button pressed", mDriverController.b()); */

mDriverController
.x()
Expand Down
13 changes: 5 additions & 8 deletions src/main/java/com/team1701/robot/commands/Shoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ public void initialize() {
shooterAngleFromHorizontal = new Rotation2d(
distanceToTarget - Constants.Shooter.kShooterAxisOffset,
FieldConstants.kBlueSpeakerOpeningCenter.getZ() - Constants.Shooter.kShooterAxisHeight);
mShooter.setRotationBrake(true);
}

@Override
Expand All @@ -51,13 +52,10 @@ public void execute() {
mDrive, robotRelativeRotationDemand, Constants.Drive.kFastKinematicLimits, true);
}
// TODO add throughBoreEncoder
if (true /* TODO throughBoreEncoder is not at position (within tolerance) */) {
mShooter.setRotationAngle(shooterAngleFromHorizontal);
} else {
// TODO: add check for value change
mShooter.setRotationBrake(true);
mShooter.setRollerSpeed(Units.rotationsPerMinuteToRadiansPerSecond(Constants.Motors.kMaxKrakenRPM));
}
mShooter.setRotationAngle(shooterAngleFromHorizontal);

// TODO: add check for value change
mShooter.setRollerSpeed(Units.rotationsPerMinuteToRadiansPerSecond(Constants.Motors.kMaxKrakenRPM));
// TODO: implement autostart/stop with sensors

if (true /* TODO !shooterHasPiece */) {
Expand All @@ -69,7 +67,6 @@ public void execute() {
@Override
public void end(boolean interrupted) {
mShooter.stopRollers();
mShooter.setRotationBrake(false); // so angle can be continually adjusted
}

@Override
Expand Down
Loading

0 comments on commit d237174

Please sign in to comment.