Skip to content

Commit

Permalink
Amp scoring action and Mechanism2d (#51)
Browse files Browse the repository at this point in the history
* Adds HoodIOs and integrates into ScoringSubsystem

* Adds mechanism2d for scoring subsystem

* Flips hood to correct side

* Tunes hood to be reasonable and visible

* Fixes minor intake bugs

* Fixes aiming latency

* Reformats scoring constants
  • Loading branch information
honzikschenk authored Jan 25, 2024
1 parent 3159c2e commit fa9ac99
Show file tree
Hide file tree
Showing 12 changed files with 277 additions and 30 deletions.
7 changes: 6 additions & 1 deletion simgui-ds.json
Original file line number Diff line number Diff line change
@@ -1,4 +1,9 @@
{
"FMS": {
"window": {
"visible": false
}
},
"keyboardJoysticks": [
{
"axisConfig": [
Expand Down Expand Up @@ -93,7 +98,7 @@
{},
{},
{
"guid": "03000000550900001472000000000000",
"guid": "78696e70757401000000000000000000",
"useGamepad": true
}
]
Expand Down
14 changes: 14 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,21 @@
"window": {
"visible": true
}
},
"Other Devices": {
"window": {
"visible": false
}
},
"Timing": {
"window": {
"visible": false
}
}
},
"NTProvider": {
"types": {
"/AdvantageKit/RealOutputs/scoring/mechanism2d": "Mechanism2d",
"/FMSInfo": "FMSInfo",
"/Pose": "Field2d",
"/SmartDashboard/Module 0": "Mechanism2d",
Expand All @@ -18,5 +29,8 @@
},
"NetworkTables Info": {
"visible": true
},
"NetworkTables View": {
"visible": false
}
}
26 changes: 20 additions & 6 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -275,8 +275,8 @@ public static final class TunerConstants {

public static final class ScoringConstants {
public static final double aimerkP = 6.0;
public static final double aimerkI = 0.0;
public static final double aimerkD = 1.0;
public static final double aimerkI = 0.4;
public static final double aimerkD = 2.5;

public static final double aimerkS = 0.0;
public static final double aimerkG = 0.0;
Expand All @@ -291,24 +291,38 @@ public static final class ScoringConstants {
public static final double shooterkV = 0.0;
public static final double shooterkA = 0.0;

public static final double hoodkP = 0.02;
public static final double hoodkI = 0.0;
public static final double hoodkD = 0.6;

public static final int aimLeftMotorId = 9;
public static final int aimRightMotorId = 10;

public static final int shooterLeftMotorId = 11;
public static final int shooterRightMotorId = 12;

public static final int aimEncoderPort = 0; // TODO: Change

public static final int kickerMotorId = 13;

public static final int hoodId = 14;

public static final int aimEncoderPort = 0; // TODO: Change

public static final double aimAcceleration = 1;
public static final double aimCruiseVelocity = 1;

public static final double shooterAcceleration = 1;
public static final double shooterJerk = 1;

public static final double shooterVelocityRPMMargin = 0;
public static final double aimAngleRadiansMargin = 0;
public static final double shooterVelocityMarginRPM = 10;
public static final double aimAngleMarginRadians = Units.degreesToRadians(5);
public static final double hoodAngleMarginRadians = Units.degreesToRadians(5);

public static final double intakeAngleToleranceRadians =
Math.PI / 2 - Units.degreesToRadians(40);

public static final double shooterAmpVelocityRPM = 10;

public static final double aimMaxAngleRadians = Math.PI / 2;

// NOTE - These should be monotonically increasing
// Key - Distance in meters
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
import frc.robot.subsystems.localization.VisionLocalizer;
import frc.robot.subsystems.scoring.AimerIOSim;
import frc.robot.subsystems.scoring.AimerIOTalon;
import frc.robot.subsystems.scoring.HoodIOSim;
import frc.robot.subsystems.scoring.HoodIOVortex;
import frc.robot.subsystems.scoring.ScoringSubsystem;
import frc.robot.subsystems.scoring.ShooterIOSim;
import frc.robot.subsystems.scoring.ShooterIOTalon;
Expand Down Expand Up @@ -76,6 +78,11 @@ private void configureBindings() {
.onFalse(new InstantCommand(
() -> scoringSubsystem.setAction(
ScoringSubsystem.ScoringAction.WAIT)));

controller.povUp()
.onTrue(new InstantCommand(
() -> scoringSubsystem.setAction(
ScoringSubsystem.ScoringAction.AMP_AIM)));

controller.start()
.onTrue(new InstantCommand(
Expand All @@ -92,6 +99,7 @@ public void configureSubsystems() {
new ScoringSubsystem(
new ShooterIOTalon(),
new AimerIOTalon(),
new HoodIOVortex(),
driveTelemetry::getFieldToRobot);

tagVision = new VisionLocalizer(new VisionIOReal(VisionConstants.cameras));
Expand All @@ -104,6 +112,7 @@ public void configureSubsystems() {
new ScoringSubsystem(
new ShooterIOSim(),
new AimerIOSim(),
new HoodIOSim(),
driveTelemetry::getFieldToRobot);

tagVision =
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/scoring/AimerIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,5 +13,5 @@ public static class AimerIOInputs {

public default void updateInputs(AimerIOInputs inputs) {}

public default void setAimAngleRad(double angle) {}
public default void setAimAngleRad(double angle, boolean newProfile) {}
}
14 changes: 6 additions & 8 deletions src/main/java/frc/robot/subsystems/scoring/AimerIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,11 @@ public class AimerIOSim implements AimerIO {
private final SingleJointedArmSim sim =
new SingleJointedArmSim(
DCMotor.getNeoVortex(2),
1.0,
1.5,
SingleJointedArmSim.estimateMOI(0.5, 4.5),
0.5,
0.0,
2.0,
ScoringConstants.aimMaxAngleRadians,
false,
0.0);
private final PIDController controller =
Expand All @@ -32,7 +32,7 @@ public class AimerIOSim implements AimerIO {
ScoringConstants.aimerkV,
ScoringConstants.aimerkA);
private final TrapezoidProfile profile =
new TrapezoidProfile(new TrapezoidProfile.Constraints(0.8, 0.4));
new TrapezoidProfile(new TrapezoidProfile.Constraints(0.8, 0.5));

private final Timer timer = new Timer();

Expand All @@ -43,8 +43,8 @@ public class AimerIOSim implements AimerIO {
double initialVelocity = 0.0;

@Override
public void setAimAngleRad(double angle) {
if (goalAngleRad != angle) {
public void setAimAngleRad(double angle, boolean newProfile) {
if (goalAngleRad != angle && newProfile) {
timer.reset();
timer.start();

Expand All @@ -67,11 +67,9 @@ public void updateInputs(AimerIOInputs inputs) {
appliedVolts =
feedforward.calculate(trapezoidSetpoint.position, trapezoidSetpoint.velocity)
+ controller.calculate(sim.getAngleRads(), trapezoidSetpoint.position);
// appliedVolts = controller.calculate(sim.getAngleRads(), goalAngleRad);
sim.setInputVoltage(appliedVolts);

// inputs.aimGoalAngleRad = goalAngleRad;
inputs.aimGoalAngleRad = trapezoidSetpoint.position;
inputs.aimGoalAngleRad = goalAngleRad;
inputs.aimAngleRad = sim.getAngleRads();

inputs.aimAppliedVolts = appliedVolts;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ public AimerIOTalon() {
}

@Override
public void setAimAngleRad(double angle) {
public void setAimAngleRad(double angle, boolean newProfile) {
goalAngleRad = angle;
}

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

import org.littletonrobotics.junction.AutoLog;

public interface HoodIO {
@AutoLog
public static class HoodIOInputs {
public double hoodAngleRad = 0.0;
public double hoodGoalAngleRad = 0.0;
public double hoodAppliedVolts = 0.0;
public double hoodCurrentAmps = 0.0;
}

public default void updateInputs(HoodIOInputs inputs) {}

public default void setHoodAngleRad(double angle) {}
}
45 changes: 45 additions & 0 deletions src/main/java/frc/robot/subsystems/scoring/HoodIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
package frc.robot.subsystems.scoring;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import frc.robot.Constants;
import frc.robot.Constants.ScoringConstants;

public class HoodIOSim implements HoodIO {
private final SingleJointedArmSim sim =
new SingleJointedArmSim(
DCMotor.getNeoVortex(1),
0.2,
SingleJointedArmSim.estimateMOI(0.1, 2),
0.1,
0.0,
Math.PI,
false,
0.0);
private final PIDController controller =
new PIDController(
ScoringConstants.aimerkP, ScoringConstants.aimerkI, ScoringConstants.aimerkD);

double goalAngleRad = 0.0;
double appliedVolts = 0.0;

@Override
public void setHoodAngleRad(double angle) {
goalAngleRad = angle;
}

@Override
public void updateInputs(HoodIOInputs inputs) {
sim.update(Constants.loopTime);

appliedVolts = controller.calculate(sim.getAngleRads(), goalAngleRad);
sim.setInputVoltage(appliedVolts);

inputs.hoodAngleRad = sim.getAngleRads();
inputs.hoodGoalAngleRad = goalAngleRad;

inputs.hoodAppliedVolts = appliedVolts;
inputs.hoodCurrentAmps = sim.getCurrentDrawAmps();
}
}
39 changes: 39 additions & 0 deletions src/main/java/frc/robot/subsystems/scoring/HoodIOVortex.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
// FIXME: Fix once we get the real robot
package frc.robot.subsystems.scoring;

import com.revrobotics.CANSparkFlex;
import frc.robot.Constants.ScoringConstants;

public class HoodIOVortex implements HoodIO {
private final CANSparkFlex hoodMotor =
new CANSparkFlex(ScoringConstants.hoodId, CANSparkFlex.MotorType.kBrushless);

double goalAngleRad = 0.0;

public HoodIOVortex() {
hoodMotor.setSmartCurrentLimit(10);

hoodMotor.getPIDController().setP(ScoringConstants.hoodkP);
hoodMotor.getPIDController().setI(ScoringConstants.hoodkI);
hoodMotor.getPIDController().setD(ScoringConstants.hoodkD);

hoodMotor.getEncoder().setPosition(0);

// TODO: Get position later
// hoodMotor.getEncoder().setPositionConversionFactor()
}

@Override
public void setHoodAngleRad(double angle) {
goalAngleRad = angle;
}

@Override
public void updateInputs(HoodIOInputs inputs) {
inputs.hoodAngleRad = hoodMotor.getEncoder().getPosition();
inputs.hoodGoalAngleRad = goalAngleRad;

inputs.hoodAppliedVolts = hoodMotor.getAppliedOutput();
inputs.hoodCurrentAmps = hoodMotor.getOutputCurrent();
}
}
Loading

0 comments on commit fa9ac99

Please sign in to comment.