Skip to content

Commit

Permalink
spotless (damn it raf)
Browse files Browse the repository at this point in the history
  • Loading branch information
mattperls-code committed Feb 17, 2024
1 parent 155ee25 commit cedd9f1
Show file tree
Hide file tree
Showing 10 changed files with 186 additions and 188 deletions.
17 changes: 8 additions & 9 deletions src/main/java/org/robolancers321/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,6 @@
package org.robolancers321;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.commands.PathPlannerAuto;
import com.pathplanner.lib.path.GoalEndState;
import com.pathplanner.lib.path.PathPlannerPath;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -45,13 +40,17 @@ private void configureBindings() {

new Trigger(this.driverController::getAButton).onTrue(this.drivetrain.zeroYaw());

new Trigger(() -> this.driverController.getRightTriggerAxis() > 0.8).onTrue(this.intake.retractor.moveToIntake());
new Trigger(() -> this.driverController.getRightTriggerAxis() > 0.8)
.onTrue(this.intake.retractor.moveToIntake());

new Trigger(() -> this.driverController.getRightTriggerAxis() > 0.8).onFalse(this.intake.retractor.moveToRetracted());
new Trigger(() -> this.driverController.getRightTriggerAxis() > 0.8)
.onFalse(this.intake.retractor.moveToRetracted());

new Trigger(() -> this.manipulatorController.getRightTriggerAxis() > 0.8).onTrue(this.launcher.pivot.aimAtAmp());
new Trigger(() -> this.manipulatorController.getRightTriggerAxis() > 0.8)
.onTrue(this.launcher.pivot.aimAtAmp());

new Trigger(() -> this.manipulatorController.getRightTriggerAxis() > 0.8).onFalse(this.launcher.pivot.moveToRetracted());
new Trigger(() -> this.manipulatorController.getRightTriggerAxis() > 0.8)
.onFalse(this.launcher.pivot.moveToRetracted());
}

private void configureAutoChooser() {
Expand Down
2 changes: 0 additions & 2 deletions src/main/java/org/robolancers321/commands/Mate.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
/* (C) Robolancers 2024 */
package org.robolancers321.commands;

import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.ParallelRaceGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import java.util.function.DoubleSupplier;
import org.robolancers321.subsystems.intake.Intake;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@
import org.photonvision.PhotonCamera;
import org.photonvision.PhotonPoseEstimator;
import org.photonvision.PhotonPoseEstimator.PoseStrategy;
import org.photonvision.proto.Photon;
import org.photonvision.targeting.PhotonPipelineResult;
import org.photonvision.targeting.PhotonTrackedTarget;

Expand Down Expand Up @@ -67,9 +66,11 @@ public static Drivetrain getInstance() {
// TODO: find this transform
private static final Transform3d kRobotToCameraTransform =
new Transform3d(0, 0, 0, new Rotation3d(0, Math.PI, 0));

private static final double kNoteCameraMountHeight = Units.inchesToMeters(11.0); // rough estimate of camera height while mounted on crate
private static final double kNoteCameraMountPitch = 0.0; // degrees w/r to the horizontal, above horizontal is positive

private static final double kNoteCameraMountHeight =
Units.inchesToMeters(11.0); // rough estimate of camera height while mounted on crate
private static final double kNoteCameraMountPitch =
0.0; // degrees w/r to the horizontal, above horizontal is positive

private static final double kTrackWidthMeters = Units.inchesToMeters(17.5);
private static final double kWheelBaseMeters = Units.inchesToMeters(17.5);
Expand Down Expand Up @@ -264,15 +265,17 @@ private void fuseVision() {
visionEstimate.get().estimatedPose.toPose2d(), visionEstimate.get().timestampSeconds);
}

private Translation2d getRelativeNoteLocation(){
private Translation2d getRelativeNoteLocation() {
PhotonPipelineResult latestResult = this.noteCamera.getLatestResult();

if (!latestResult.hasTargets()) return new Translation2d();

PhotonTrackedTarget bestTarget = latestResult.getBestTarget();

// TODO: plus or minus mount pitch?
double dz = kNoteCameraMountHeight / Math.tan((-bestTarget.getPitch() + kNoteCameraMountPitch) * Math.PI / 180.0);
double dz =
kNoteCameraMountHeight
/ Math.tan((-bestTarget.getPitch() + kNoteCameraMountPitch) * Math.PI / 180.0);
double dx = dz * Math.tan(bestTarget.getYaw() * Math.PI / 180.0);

return new Translation2d(dx, dz);
Expand Down
35 changes: 23 additions & 12 deletions src/main/java/org/robolancers321/subsystems/intake/Retractor.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import com.revrobotics.CANSparkBase.SoftLimitDirection;
import com.revrobotics.CANSparkMax;
import com.revrobotics.SparkAbsoluteEncoder.Type;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.ProfiledPIDController;
Expand Down Expand Up @@ -41,7 +40,7 @@ public static Retractor getInstance() {
private static final boolean kInvertEncoder = true;

private static final int kCurrentLimit = 40;

private static final double kGearRatio = 360.0;

private static final float kMinAngle = -20.0f;
Expand Down Expand Up @@ -105,7 +104,7 @@ private void configureMotor() {
// this.motor.setSoftLimit(CANSparkBase.SoftLimitDirection.kReverse, (float) kMinAngle);
// this.motor.enableSoftLimit(CANSparkBase.SoftLimitDirection.kForward, true);
// this.motor.enableSoftLimit(CANSparkBase.SoftLimitDirection.kReverse, true);

this.motor.enableSoftLimit(SoftLimitDirection.kForward, false);
this.motor.enableSoftLimit(SoftLimitDirection.kReverse, false);
}
Expand All @@ -126,14 +125,16 @@ private void configureController() {

this.m_enabled = true;
}

@Override
public double getMeasurement() {
return this.getPositionDeg();
}

public double getPositionDeg() {
return this.encoder.getPosition() > 180 ? this.encoder.getPosition() - 360.0 : this.encoder.getPosition();
return this.encoder.getPosition() > 180
? this.encoder.getPosition() - 360.0
: this.encoder.getPosition();
}

public double getVelocityDeg() {
Expand All @@ -147,7 +148,8 @@ private boolean atGoal() {
@Override
protected void useOutput(double output, TrapezoidProfile.State setpoint) {
double feedforwardOutput =
this.feedforwardController.calculate(setpoint.position * Math.PI / 180.0, setpoint.velocity * Math.PI / 180.0);
this.feedforwardController.calculate(
setpoint.position * Math.PI / 180.0, setpoint.velocity * Math.PI / 180.0);

SmartDashboard.putNumber("retractor position setpoint mp (deg)", setpoint.position);
SmartDashboard.putNumber("retractor velocity setpoint mp (deg)", setpoint.velocity);
Expand All @@ -170,7 +172,7 @@ private void doSendables() {
SmartDashboard.putNumber("retractor position (deg)", this.getPositionDeg());
SmartDashboard.putNumber("retractor velocity (deg)", this.getVelocityDeg());
}

@Override
public void periodic() {
super.periodic();
Expand All @@ -187,8 +189,12 @@ private void initTuning() {
SmartDashboard.putNumber("retractor kv", SmartDashboard.getNumber("retractor kv", kV));
SmartDashboard.putNumber("retractor kg", SmartDashboard.getNumber("retractor kg", kG));

SmartDashboard.putNumber("retractor max vel (deg)", SmartDashboard.getNumber("retractor max vel (deg)", kMaxVelocityDeg));
SmartDashboard.putNumber("retractor max acc (deg)", SmartDashboard.getNumber("retractor max acc (deg)", kMaxAccelerationDeg));
SmartDashboard.putNumber(
"retractor max vel (deg)",
SmartDashboard.getNumber("retractor max vel (deg)", kMaxVelocityDeg));
SmartDashboard.putNumber(
"retractor max acc (deg)",
SmartDashboard.getNumber("retractor max acc (deg)", kMaxAccelerationDeg));

SmartDashboard.putNumber("retractor target position (deg)", this.getPositionDeg());
}
Expand All @@ -211,11 +217,16 @@ private void tune() {

this.m_controller.setConstraints(new Constraints(tunedMaxVel, tunedMaxAcc));

this.setGoal(MathUtil.clamp(SmartDashboard.getNumber("retractor target position (deg)", this.getPositionDeg()), kMinAngle, kMaxAngle));
this.setGoal(
MathUtil.clamp(
SmartDashboard.getNumber("retractor target position (deg)", this.getPositionDeg()),
kMinAngle,
kMaxAngle));
}

private Command moveToAngle(double angleDeg) {
return run(() -> this.setGoal(MathUtil.clamp(angleDeg, kMinAngle, kMaxAngle))).until(this::atGoal);
return run(() -> this.setGoal(MathUtil.clamp(angleDeg, kMinAngle, kMaxAngle)))
.until(this::atGoal);
}

public Command moveToRetracted() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,12 +42,12 @@ private static AimCharacteristic calculateSpeakerAimCharacteristic(double distan
double lowerBound = keys.get(0);
double upperBound = keys.get(keys.size() - 1);

if (distance < lowerBound){
if (distance < lowerBound) {
AimTable.AimCharacteristic lowerValue = table.get(lowerBound);

return new AimTable.AimCharacteristic(lowerValue.angle, lowerValue.rpm);
}

if (distance > upperBound) {
AimTable.AimCharacteristic upperValue = table.get(upperBound);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@

import com.revrobotics.*;
import com.revrobotics.CANSparkBase.ControlType;

import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
Expand Down Expand Up @@ -40,7 +38,7 @@ private enum FlywheelSetpoint {

public final double rpm;

private FlywheelSetpoint(double rpm){
private FlywheelSetpoint(double rpm) {
this.rpm = rpm;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

import com.revrobotics.*;
import com.revrobotics.CANSparkBase.ControlType;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.ParallelRaceGroup;
Expand Down
10 changes: 0 additions & 10 deletions src/main/java/org/robolancers321/subsystems/launcher/Launcher.java
Original file line number Diff line number Diff line change
@@ -1,17 +1,7 @@
/* (C) Robolancers 2024 */
package org.robolancers321.subsystems.launcher;

import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.ParallelRaceGroup;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
import java.util.function.DoubleSupplier;

public class Launcher extends SubsystemBase {
/*
Expand Down
27 changes: 19 additions & 8 deletions src/main/java/org/robolancers321/subsystems/launcher/Pivot.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
import com.revrobotics.*;
import com.revrobotics.CANSparkBase.SoftLimitDirection;
import com.revrobotics.SparkAbsoluteEncoder.Type;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.ProfiledPIDController;
Expand Down Expand Up @@ -129,9 +128,11 @@ private void configureController() {
public double getMeasurement() {
return this.getPositionDeg();
}

public double getPositionDeg() {
return this.encoder.getPosition() > 180 ? this.encoder.getPosition() - 360.0 : this.encoder.getPosition();
return this.encoder.getPosition() > 180
? this.encoder.getPosition() - 360.0
: this.encoder.getPosition();
}

public double getVelocityDeg() {
Expand All @@ -145,7 +146,8 @@ private boolean atGoal() {
@Override
protected void useOutput(double output, TrapezoidProfile.State setpoint) {
double feedforwardOutput =
this.feedforwardController.calculate(setpoint.position * Math.PI / 180.0, setpoint.velocity * Math.PI / 180.0);
this.feedforwardController.calculate(
setpoint.position * Math.PI / 180.0, setpoint.velocity * Math.PI / 180.0);

SmartDashboard.putNumber("pivot position setpoint mp (deg)", setpoint.position);
SmartDashboard.putNumber("pivot velocity setpoint mp (deg)", setpoint.velocity);
Expand Down Expand Up @@ -184,8 +186,11 @@ private void initTuning() {
SmartDashboard.putNumber("pivot kg", SmartDashboard.getNumber("pivot kg", kG));
SmartDashboard.putNumber("pivot kv", SmartDashboard.getNumber("pivot kv", kV));

SmartDashboard.putNumber("pivot max vel (deg)", SmartDashboard.getNumber("pivot max vel (deg)", kMaxVelocityDeg));
SmartDashboard.putNumber("pivot max acc (deg)", SmartDashboard.getNumber("pivot max acc (deg)", kMaxAccelerationDeg));
SmartDashboard.putNumber(
"pivot max vel (deg)", SmartDashboard.getNumber("pivot max vel (deg)", kMaxVelocityDeg));
SmartDashboard.putNumber(
"pivot max acc (deg)",
SmartDashboard.getNumber("pivot max acc (deg)", kMaxAccelerationDeg));

SmartDashboard.putNumber("pivot target position (deg)", this.getPositionDeg());
}
Expand All @@ -208,11 +213,17 @@ private void tune() {

this.m_controller.setConstraints(new Constraints(tunedMaxVel, tunedMaxAcc));

this.setGoal(MathUtil.clamp(SmartDashboard.getNumber("pivot target position (deg)", this.getPositionDeg()), kMinAngle, kMaxAngle));
this.setGoal(
MathUtil.clamp(
SmartDashboard.getNumber("pivot target position (deg)", this.getPositionDeg()),
kMinAngle,
kMaxAngle));
}

private Command moveToAngle(DoubleSupplier angleDegSupplier) {
return run(() -> this.setGoal(MathUtil.clamp(angleDegSupplier.getAsDouble(), kMinAngle, kMaxAngle))).until(this::atGoal);
return run(() ->
this.setGoal(MathUtil.clamp(angleDegSupplier.getAsDouble(), kMinAngle, kMaxAngle)))
.until(this::atGoal);
}

private Command moveToAngle(double angleDeg) {
Expand Down
Loading

0 comments on commit cedd9f1

Please sign in to comment.