Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 0dc9253

Browse files
committed
refactor(odometry): Continue WIP.
1 parent 372b847 commit 0dc9253

File tree

11 files changed

+83
-1270
lines changed

11 files changed

+83
-1270
lines changed

src/main/java/frc/lib/LimelightHelpers.java

Lines changed: 0 additions & 1115 deletions
This file was deleted.

src/main/java/frc/robot/odometry/GyroscopeIO.java renamed to src/main/java/frc/lib/sensor/GyroscopeIO.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
1-
package frc.robot.odometry;
1+
package frc.lib.sensor;
22

3-
/** Gyroscope hardware interface. */
3+
/** Gyroscope interface. */
44
public interface GyroscopeIO {
55

6-
/** Gyroscope's hardware interface. */
6+
/** Gyroscope interface. */
77
public static class GyroscopeIOValues {
88
/** Roll angle in rotations. */
99
public double rollRotations = 0.0;
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package frc.robot.odometry;
1+
package frc.lib.sensor;
22

33
import com.ctre.phoenix6.BaseStatusSignal;
44
import com.ctre.phoenix6.StatusSignal;
@@ -10,30 +10,27 @@
1010
/** Pigeon 2 gyroscope. */
1111
public class GyroscopeIOPigeon2 implements GyroscopeIO {
1212

13-
/** Hardware Pigeon 2. */
14-
private final Pigeon2 pigeon2;
13+
/** Pigeon 2. */
14+
private final Pigeon2 gyroscope;
1515

16-
/** Pigeon 2's roll, pitch, and yaw status signals. */
16+
/** Pigeon 2 status signals. */
1717
private final StatusSignal<Double> roll, pitch, yaw, rollVelocity, pitchVelocity, yawVelocity;
1818

19-
/** Creates a new Pigeon 2 gyroscope. */
2019
public GyroscopeIOPigeon2() {
21-
pigeon2 = new Pigeon2(0, "swerve");
20+
gyroscope = new Pigeon2(0, "swerve");
2221

23-
roll = pigeon2.getRoll();
24-
pitch = pigeon2.getPitch();
25-
yaw = pigeon2.getYaw();
22+
roll = gyroscope.getRoll();
23+
pitch = gyroscope.getPitch();
24+
yaw = gyroscope.getYaw();
2625

27-
rollVelocity = pigeon2.getAngularVelocityXWorld();
28-
pitchVelocity = pigeon2.getAngularVelocityYWorld();
29-
yawVelocity = pigeon2.getAngularVelocityZWorld();
26+
rollVelocity = gyroscope.getAngularVelocityXWorld();
27+
pitchVelocity = gyroscope.getAngularVelocityYWorld();
28+
yawVelocity = gyroscope.getAngularVelocityZWorld();
3029
}
3130

3231
@Override
3332
public void configure() {
34-
Pigeon2Configuration config = OdometryFactory.createGyroscopeConfig();
35-
36-
Configurator.configurePigeon2(pigeon2.getConfigurator(), config);
33+
Configurator.configurePigeon2(gyroscope.getConfigurator(), new Pigeon2Configuration());
3734
}
3835

3936
@Override
@@ -51,6 +48,6 @@ public void update(GyroscopeIOValues values) {
5148

5249
@Override
5350
public void setYaw(double yawRotations) {
54-
pigeon2.setYaw(Units.rotationsToDegrees(yawRotations));
51+
gyroscope.setYaw(Units.rotationsToDegrees(yawRotations));
5552
}
5653
}
Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,36 @@
1+
package frc.lib.sensor;
2+
3+
import frc.robot.RobotConstants;
4+
import java.util.function.DoubleSupplier;
5+
6+
/** Simulated gyroscope. */
7+
public class GyroscopeIOSim implements GyroscopeIO {
8+
9+
/** Yaw velocity supplier in rotations per second */
10+
private final DoubleSupplier yawVelocityRotationsPerSecond;
11+
12+
/** Yaw in rotations. */
13+
private double yawRotations = 0.0;
14+
15+
/** Creates a new simulated gyroscope. */
16+
public GyroscopeIOSim(DoubleSupplier yawVelocityRotationsPerSecond) {
17+
this.yawVelocityRotationsPerSecond = yawVelocityRotationsPerSecond;
18+
}
19+
20+
@Override
21+
public void configure() {}
22+
23+
@Override
24+
public void update(GyroscopeIOValues values) {
25+
yawRotations += yawVelocityRotationsPerSecond.getAsDouble() * RobotConstants.PERIODIC_DURATION;
26+
27+
values.yawRotations = yawRotations;
28+
29+
values.yawVelocityRotations = yawVelocityRotationsPerSecond.getAsDouble();
30+
}
31+
32+
@Override
33+
public void setYaw(double yawRotations) {
34+
this.yawRotations = yawRotations;
35+
}
36+
}

src/main/java/frc/robot/arm/ArmFactory.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ public class ArmFactory {
1515
/**
1616
* Creates the shoulder controller.
1717
*
18+
* @param config the shoulder controller config.
1819
* @return the shoulder controller.
1920
*/
2021
public static PositionControllerIO createShoulder(MechanismConfig config) {

src/main/java/frc/robot/intake/IntakeFactory.java

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,9 +9,15 @@
99
import frc.robot.RobotConstants;
1010
import frc.robot.RobotConstants.Subsystem;
1111

12-
/** Helper class for creating hardware for the intake subsystem. */
12+
/** Factory for creating intake subsystem hardware. */
1313
public class IntakeFactory {
1414

15+
/**
16+
* Creates the front roller controller.
17+
*
18+
* @param config the front roller controller config.
19+
* @return the front roller controller.
20+
*/
1521
public static VelocityControllerIO createFrontRoller(MechanismConfig config) {
1622
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.INTAKE)) {
1723
return new VelocityControllerIOTalonFXPIDF(new CAN(50), config);
@@ -20,6 +26,12 @@ public static VelocityControllerIO createFrontRoller(MechanismConfig config) {
2026
return new VelocityControllerIOSim();
2127
}
2228

29+
/**
30+
* Creates the back roller controller.
31+
*
32+
* @param config the back roller controller config.
33+
* @return the back roller controller.
34+
*/
2335
public static VelocityControllerIO createBackRoller(MechanismConfig config) {
2436
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.INTAKE)) {
2537
return new VelocityControllerIOTalonFXPIDF(new CAN(40), config);

src/main/java/frc/robot/odometry/GyroscopeIOSim.java

Lines changed: 0 additions & 38 deletions
This file was deleted.

src/main/java/frc/robot/odometry/Limelight.java

Lines changed: 0 additions & 37 deletions
This file was deleted.

src/main/java/frc/robot/odometry/Odometry.java

Lines changed: 9 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
package frc.robot.odometry;
22

3-
import edu.wpi.first.math.VecBuilder;
43
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
54
import edu.wpi.first.math.geometry.Pose2d;
65
import edu.wpi.first.math.geometry.Rotation2d;
@@ -16,17 +15,15 @@
1615
import frc.lib.AllianceFlipHelper;
1716
import frc.lib.Subsystem;
1817
import frc.lib.Telemetry;
19-
import frc.robot.odometry.GyroscopeIO.GyroscopeIOValues;
18+
import frc.lib.sensor.GyroscopeIO;
19+
import frc.lib.sensor.GyroscopeIO.GyroscopeIOValues;
2020
import frc.robot.swerve.Swerve;
21-
import java.util.ArrayList;
22-
import java.util.List;
23-
import java.util.function.Consumer;
2421
import java.util.function.Supplier;
2522

26-
/** Subsystem class for the odometry subsystem. */
23+
/** Odometry subsystem. */
2724
public class Odometry extends Subsystem {
2825

29-
/** Instance variable for the odometry subsystem singleton. */
26+
/** Odometry singleton. */
3027
private static Odometry instance = null;
3128

3229
/** Gyroscope. */
@@ -47,10 +44,7 @@ public class Odometry extends Subsystem {
4744
/** Field. */
4845
private final Field2d field;
4946

50-
/** List of functions to be called when pose is manually updated. */
51-
private final List<Consumer<Rotation2d>> yawUpdateConsumers;
52-
53-
/** Creates a new instance of the odometry subsystem. */
47+
/** Initializes the odometry subsystem and configures odometry hardware. */
5448
private Odometry() {
5549
gyroscope = OdometryFactory.createGyroscope(this);
5650
gyroscope.configure();
@@ -61,21 +55,14 @@ private Odometry() {
6155

6256
gyroscope.update(gyroscopeValues);
6357

64-
Rotation2d initialGyroRotation = Rotation2d.fromRotations(gyroscopeValues.yawRotations);
65-
66-
Pose2d initialPose = new Pose2d();
67-
6858
swervePoseEstimator =
6959
new SwerveDrivePoseEstimator(
7060
Swerve.getInstance().getKinematics(),
71-
initialGyroRotation,
61+
Rotation2d.fromRotations(gyroscopeValues.yawRotations),
7262
swerveModulePositionsSupplier.get(),
73-
initialPose);
74-
swervePoseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(.7, .7, 9999999));
63+
new Pose2d());
7564

7665
field = new Field2d();
77-
78-
yawUpdateConsumers = new ArrayList<Consumer<Rotation2d>>();
7966
}
8067

8168
/**
@@ -142,6 +129,8 @@ public Pose2d getPosition() {
142129
* @return the rotation of the robot on the field where zero is away from the blue alliance wall.
143130
*/
144131
public Rotation2d getFieldRelativeHeading() {
132+
// TODO Doesn't obey WPILib's coordinate system
133+
145134
return getPosition().getRotation();
146135
}
147136

@@ -153,8 +142,6 @@ public Rotation2d getFieldRelativeHeading() {
153142
* alliance.
154143
*/
155144
public Rotation2d getDriverRelativeHeading() {
156-
gyroscope.update(gyroscopeValues);
157-
158145
return Rotation2d.fromRotations(gyroscopeValues.yawRotations);
159146
}
160147

@@ -181,15 +168,6 @@ public void setRotation(Rotation2d rotation) {
181168
setPosition(new Pose2d(position.getTranslation(), rotation));
182169
}
183170

184-
/**
185-
* Adds a consumer for when pose is manually updated.
186-
*
187-
* @param consumer consumer for when pose is manually updated.
188-
*/
189-
public void onYawUpdate(Consumer<Rotation2d> consumer) {
190-
yawUpdateConsumers.add(consumer);
191-
}
192-
193171
/**
194172
* Zeroes the driver-relative rotation of the robot.
195173
*
@@ -199,8 +177,6 @@ public Command tare() {
199177
return Commands.runOnce(
200178
() -> {
201179
gyroscope.setYaw(0.0);
202-
203-
yawUpdateConsumers.forEach(consumer -> consumer.accept(Rotation2d.fromDegrees(0)));
204180
});
205181
}
206182

src/main/java/frc/robot/odometry/OdometryConstants.java

Lines changed: 0 additions & 9 deletions
This file was deleted.
Lines changed: 8 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -1,35 +1,25 @@
11
package frc.robot.odometry;
22

3-
import com.ctre.phoenix6.configs.Pigeon2Configuration;
3+
import edu.wpi.first.math.util.Units;
4+
import frc.lib.sensor.GyroscopeIO;
5+
import frc.lib.sensor.GyroscopeIOPigeon2;
6+
import frc.lib.sensor.GyroscopeIOSim;
47
import frc.robot.Robot;
58
import frc.robot.RobotConstants;
69
import frc.robot.RobotConstants.Subsystem;
710

8-
/** Helper class for creating hardware for the odometry subsystem. */
11+
/** Factory for creating odometry subsystem hardware. */
912
public class OdometryFactory {
1013

1114
/**
12-
* Creates a gyroscope.
15+
* Creates the gyroscope.
1316
*
14-
* @return a gyroscope.
17+
* @return the gyroscope.
1518
*/
1619
public static GyroscopeIO createGyroscope(Odometry odometry) {
1720
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.ODOMETRY))
1821
return new GyroscopeIOPigeon2();
1922

20-
return new GyroscopeIOSim(odometry);
21-
}
22-
23-
/**
24-
* Creates a gyroscope configuration.
25-
*
26-
* @return a gyroscope configuration.
27-
*/
28-
public static Pigeon2Configuration createGyroscopeConfig() {
29-
Pigeon2Configuration gyroscopeConfig = new Pigeon2Configuration();
30-
31-
gyroscopeConfig.Pigeon2Features.EnableCompass = false;
32-
33-
return gyroscopeConfig;
23+
return new GyroscopeIOSim(() -> Units.radiansToRotations(odometry.getVelocity().dtheta));
3424
}
3525
}

0 commit comments

Comments
 (0)