Skip to content

Commit 7601fe2

Browse files
authored
Merge pull request #30 from FRC-7525/Improving-Sim-and-Logging
Improving sim and logging
2 parents c05fb6f + a8bd480 commit 7601fe2

File tree

9 files changed

+108
-44
lines changed

9 files changed

+108
-44
lines changed

misc/ControlsStuff/config.json

Lines changed: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
{
2+
"name": "Frontier",
3+
"rotations": [
4+
{
5+
"axis": "x",
6+
"degrees": 90
7+
},
8+
{
9+
"axis": "y",
10+
"degrees": 0
11+
},
12+
{
13+
"axis": "z",
14+
"degrees": 90
15+
}
16+
],
17+
"position": [
18+
0,
19+
0,
20+
0.015
21+
],
22+
"cameras": [],
23+
"components": [
24+
{
25+
"zeroedRotations": [
26+
{
27+
"axis": "x",
28+
"degrees": 90
29+
},
30+
{
31+
"axis": "z",
32+
"degrees": 90
33+
},
34+
{
35+
"axis": "y",
36+
"degrees": 0
37+
}
38+
],
39+
"zeroedPosition": [
40+
-0.355,
41+
0,
42+
-0.193
43+
]
44+
}
45+
]
46+
}

src/main/java/frc/robot/Robot.java

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
import com.pathplanner.lib.commands.PathfindingCommand;
99
import edu.wpi.first.cameraserver.CameraServer;
1010
import edu.wpi.first.wpilibj.DriverStation;
11+
import edu.wpi.first.wpilibj.RobotBase;
1112
import edu.wpi.first.wpilibj2.command.CommandScheduler;
1213
import frc.robot.AutoManager.AutoManager;
1314
import frc.robot.Manager.Manager;
@@ -60,7 +61,9 @@ public void robotInit() {
6061
@Override
6162
public void robotPeriodic() {
6263
manager.periodic();
63-
vision.periodic();
64+
if (!RobotBase.isSimulation()) {
65+
vision.periodic(); // Vision sim is broken :(
66+
}
6467
CommandScheduler.getInstance().run();
6568
Utilitys.controllers.clearCache();
6669
}

src/main/java/frc/robot/Subsystems/AlgaeCoraler/AlgaeCoraler.java

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
import static frc.robot.GlobalConstants.*;
44
import static frc.robot.Subsystems.AlgaeCoraler.AlgaeCoralerConstants.*;
55

6-
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
76
import org.littletonrobotics.junction.Logger;
87
import org.team7525.subsystem.Subsystem;
98

@@ -13,8 +12,8 @@ public class AlgaeCoraler extends Subsystem<AlgaeCoralerStates> {
1312

1413
private AlgaeCoralerIO io;
1514
private AlgaeCoralerIOInputsAutoLogged inputs;
16-
private boolean there;
17-
private AlgaeCoralerStates past;
15+
private boolean there; // If arm is at the target position
16+
private AlgaeCoralerStates past; // Previous state of the algae bar to reset there variable
1817

1918
public static AlgaeCoraler getInstance() {
2019
if (instance == null) {
@@ -46,7 +45,6 @@ public void runState() {
4645
} else if (nearTarget()) {
4746
there = true;
4847
}
49-
io.setThere(there);
5048
if (there) {
5149
io.setArmSpeed(getState().getThereSpeed());
5250
} else {
@@ -55,8 +53,9 @@ public void runState() {
5553

5654
io.updateInputs(inputs);
5755
Logger.processInputs(SUBSYSTEM_NAME, inputs);
58-
SmartDashboard.putNumber("Coral Out", CORAL_OUT_SPEED);
5956
Logger.recordOutput(SUBSYSTEM_NAME + "/State", getState().getStateString());
57+
Logger.recordOutput(SUBSYSTEM_NAME + "/isThere", there);
58+
Logger.recordOutput(SUBSYSTEM_NAME + "/Mechanism Position", io.getArmPosition());
6059
past = getState();
6160
}
6261

src/main/java/frc/robot/Subsystems/AlgaeCoraler/AlgaeCoralerConstants.java

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,6 @@ public final class AlgaeCoralerConstants {
3232
public static final int PIVOT_MOTOR_CANID = 15;
3333
public static final int SPEED_MOTOR_CANID = 5;
3434

35-
public static final Angle PIVOT_TOLERANCE = Degrees.of(1);
36-
3735
//Wheel Speeds
3836
public static final double ALGAE_IN_SPEED = -1;
3937
public static final double ALGAE_OUT_SPEED = 1;
Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
package frc.robot.Subsystems.AlgaeCoraler;
22

3+
import edu.wpi.first.math.geometry.Pose3d;
34
import org.littletonrobotics.junction.AutoLog;
45

56
public interface AlgaeCoralerIO {
@@ -9,11 +10,10 @@ public static class AlgaeCoralerIOInputs {
910
public double ArmSpeed;
1011
public double ArmSetpoint;
1112

12-
//Wheels
13+
public Pose3d ArmPosition;
14+
1315
public double wheelSpeed;
1416
public double wheelSpeedSetpoint;
15-
16-
public AlgaeCoralerStates state;
1717
}
1818

1919
public void updateInputs(AlgaeCoralerIOInputs input);
@@ -24,7 +24,7 @@ public static class AlgaeCoralerIOInputs {
2424

2525
public boolean hasCoral();
2626

27-
public void setThere(boolean there);
28-
2927
public void setArmSpeed(double ArmSpeed);
28+
29+
public Pose3d getArmPosition();
3030
}

src/main/java/frc/robot/Subsystems/AlgaeCoraler/AlgaeCoralerIOReal.java

Lines changed: 14 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -6,20 +6,19 @@
66
import com.revrobotics.spark.SparkMax;
77
import edu.wpi.first.math.filter.Debouncer;
88
import edu.wpi.first.math.filter.Debouncer.DebounceType;
9+
import edu.wpi.first.math.geometry.Pose3d;
10+
import edu.wpi.first.math.geometry.Rotation3d;
11+
import edu.wpi.first.math.util.Units;
912
import edu.wpi.first.wpilibj.DigitalInput;
1013
import org.littletonrobotics.junction.Logger;
1114

12-
// TODO: Implement Current sensing for detection of algae
13-
1415
public class AlgaeCoralerIOReal implements AlgaeCoralerIO {
1516

1617
private SparkMax wheelsMotor;
1718
private SparkMax pivotMotor;
1819

1920
private double wheelSpeedSetpoint;
2021
private DigitalInput beamBreak;
21-
private boolean motorZeroed;
22-
private Boolean there;
2322
private Debouncer debounce;
2423

2524
public AlgaeCoralerIOReal() {
@@ -30,18 +29,14 @@ public AlgaeCoralerIOReal() {
3029
debounce = new Debouncer(DEBOUNCE_TIME, DebounceType.kBoth);
3130

3231
pivotMotor.getEncoder().setPosition(0); // Zeroing the encoder
33-
34-
there = true;
3532
}
3633

3734
@Override
3835
public void updateInputs(AlgaeCoralerIOInputs inputs) {
3936
inputs.wheelSpeed = (wheelsMotor.getEncoder().getVelocity()) / 60;
4037
inputs.wheelSpeedSetpoint = wheelSpeedSetpoint;
4138

42-
Logger.recordOutput("Motors Zeroed", motorZeroed);
4339
Logger.recordOutput("Beam Break Value", beamBreak.get());
44-
Logger.recordOutput("Wheels Current", wheelsMotor.getOutputCurrent());
4540
Logger.recordOutput("Pivot Current", pivotMotor.getOutputCurrent());
4641
}
4742

@@ -70,7 +65,16 @@ public boolean hasCoral() {
7065
}
7166

7267
@Override
73-
public void setThere(boolean there) {
74-
this.there = there;
68+
public Pose3d getArmPosition() {
69+
return new Pose3d(
70+
0,
71+
0,
72+
0,
73+
new Rotation3d(
74+
0,
75+
Units.rotationsToDegrees(pivotMotor.getEncoder().getPosition()) / 25,
76+
0
77+
)
78+
);
7579
}
7680
}

src/main/java/frc/robot/Subsystems/AlgaeCoraler/AlgaeCoralerIOSim.java

Lines changed: 23 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -8,10 +8,12 @@
88
import com.revrobotics.sim.SparkMaxSim;
99
import com.revrobotics.spark.SparkLowLevel.MotorType;
1010
import com.revrobotics.spark.SparkMax;
11+
import edu.wpi.first.math.geometry.Pose3d;
12+
import edu.wpi.first.math.geometry.Rotation3d;
13+
import edu.wpi.first.math.geometry.Translation3d;
1114
import edu.wpi.first.math.system.plant.DCMotor;
1215
import edu.wpi.first.math.system.plant.LinearSystemId;
1316
import edu.wpi.first.math.util.Units;
14-
import edu.wpi.first.units.measure.Angle;
1517
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
1618
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
1719
import frc.robot.Subsystems.AlgaeCoraler.AlgaeCoralerConstants.Sim;
@@ -29,7 +31,6 @@ public class AlgaeCoralerIOSim implements AlgaeCoralerIO {
2931
private SparkMaxSim wheelSparkSim;
3032

3133
private double wheelSpeedSetpoint;
32-
private Angle pivotPosSetpoint;
3334

3435
public AlgaeCoralerIOSim() {
3536
pivotSim = new SingleJointedArmSim(
@@ -58,8 +59,6 @@ public AlgaeCoralerIOSim() {
5859
pivotSparkSim = new SparkMaxSim(dummyPivotSpark, DCMotor.getNEO(NUM_PIVOT_MOTORS));
5960

6061
wheelSparkSim = new SparkMaxSim(dummyWheelsSpark, DCMotor.getNEO(NUM_SPEED_MOTORS));
61-
62-
pivotPosSetpoint = Degrees.of(0);
6362
wheelSpeedSetpoint = 0;
6463
}
6564

@@ -94,20 +93,32 @@ public void setArmSpeed(double armSpeed) {
9493

9594
@Override
9695
public boolean nearTarget() {
97-
return (
98-
(Math.abs(
99-
Units.radiansToDegrees(pivotSim.getAngleRads()) - pivotPosSetpoint.in(Degree)
100-
) <
101-
PIVOT_TOLERANCE.in(Degrees))
102-
);
96+
return true; // In simulation, we assume the arm is always near the target
10397
}
10498

10599
@Override
106100
public boolean hasCoral() {
107101
return AlgaeCoraler.getInstance().getStateTime() > Sim.CORAL_TIME.in(Seconds);
108-
// IDK how to sim this
109102
}
110103

111104
@Override
112-
public void setThere(boolean there) {}
105+
public Pose3d getArmPosition() {
106+
return new Pose3d(
107+
new Translation3d(0.355, 0, 0.193),
108+
new Rotation3d(
109+
0,
110+
Math.toRadians(
111+
AlgaeCoraler.getInstance().getState() == AlgaeCoralerStates.IDLE ||
112+
AlgaeCoraler.getInstance().getState() == AlgaeCoralerStates.HOLDING ||
113+
AlgaeCoraler.getInstance().getState() == AlgaeCoralerStates.CORALOUT ||
114+
AlgaeCoraler.getInstance().getState() == AlgaeCoralerStates.ALGAEOUT
115+
? Math.floor(
116+
Math.max(45 - (AlgaeCoraler.getInstance().getStateTime() * 60), -10)
117+
)
118+
: Math.floor(Math.min(AlgaeCoraler.getInstance().getStateTime() * 60, 45))
119+
),
120+
0
121+
)
122+
);
123+
}
113124
}

src/main/java/frc/robot/Subsystems/Drive/Drive.java

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,5 @@
1+
// Drive Subsystem
2+
// [Rouge Subsystem: Manages it's own state]
13
package frc.robot.Subsystems.Drive;
24

35
import static frc.robot.GlobalConstants.Controllers.DRIVER_CONTROLLER;
@@ -112,15 +114,11 @@ private void establishTriggers() {
112114
public void runState() {
113115
// Slow mode toggle
114116
if (slow) {
115-
if (Controllers.DRIVER_CONTROLLER.getLeftBumperButtonPressed()) {
116-
slow = false;
117-
}
117+
if (Controllers.DRIVER_CONTROLLER.getLeftBumperButtonPressed()) slow = false;
118118
swerveInputs.scaleTranslation(0.33);
119119
swerveInputs.scaleRotation(0.33);
120120
} else {
121-
if (Controllers.DRIVER_CONTROLLER.getLeftBumperButtonPressed()) {
122-
slow = true;
123-
}
121+
if (Controllers.DRIVER_CONTROLLER.getLeftBumperButtonPressed()) slow = true;
124122
swerveInputs.scaleTranslation(1);
125123
swerveInputs.scaleRotation(1);
126124
}
@@ -138,9 +136,12 @@ public void runState() {
138136
swerveDrive.drive(swerveInputs.get());
139137
}
140138

141-
// Update SmartDashboard
142-
SmartDashboard.putBoolean("SLOW MODE", slow);
143-
SmartDashboard.putBoolean("FIELD RELATIVE", fieldRelative);
139+
// Logging Stuff
140+
field.setRobotPose(swerveDrive.getPose());
141+
Logger.recordOutput(SUBSYSTEM_NAME + "/Pose", swerveDrive.getPose());
142+
Logger.recordOutput(SUBSYSTEM_NAME + "/Slow Mode", slow);
143+
Logger.recordOutput(SUBSYSTEM_NAME + "/Field Relative", fieldRelative);
144+
Logger.recordOutput(SUBSYSTEM_NAME + "/Drive State", getState());
144145
SmartDashboard.putData(field);
145146
}
146147

src/main/java/frc/robot/Subsystems/Drive/DriveConstants.java

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
*/
1616
public final class DriveConstants {
1717

18+
public static final String SUBSYSTEM_NAME = "DriveBase";
19+
1820
// PID constants for translation and rotation
1921
public static final PIDConstants PPH_TRANSLATION_PID = new PIDConstants(5, 0, 0);
2022
public static final PIDConstants PPH_ROTATION_PID = new PIDConstants(5, 0, 0);

0 commit comments

Comments
 (0)