Skip to content

Commit

Permalink
vision configs + localization
Browse files Browse the repository at this point in the history
  • Loading branch information
jordanjcoderman committed Sep 4, 2024
1 parent 504073e commit b1c8149
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 13 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/config/CompConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import frc.robot.config.RobotConfig.QueuerConfig;
import frc.robot.config.RobotConfig.ShooterConfig;
import frc.robot.config.RobotConfig.SwerveConfig;
import frc.robot.config.RobotConfig.VisionConfig;

class CompConfig {
private static final String CANIVORE_NAME = "581CANivore";
Expand Down
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/config/RobotConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,7 @@ public record ArmConfig(
double maxAngle) {}

public record VisionConfig(
int translationHistoryArraySize,
double xyStdDev,
double thetaStdDev) {}
int translationHistoryArraySize, double xyStdDev, double thetaStdDev) {}

// TODO: Change this to false during events
public static final boolean IS_DEVELOPMENT = true;
Expand Down
31 changes: 21 additions & 10 deletions src/main/java/frc/robot/localization/LocalizationSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,24 @@
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer;
import edu.wpi.first.wpilibj.Timer;
import frc.robot.config.RobotConfig;
import frc.robot.imu.ImuSubsystem;
import frc.robot.util.scheduling.SubsystemPriority;
import frc.robot.util.state_machines.StateMachine;
import frc.robot.vision.LimelightHelpers.PoseEstimate;
import frc.robot.vision.VisionResult;
import frc.robot.vision.VisionSubsystem;
import java.util.Optional;

public class LocalizationSubsystem extends StateMachine<LocalizationState> {
private final ImuSubsystem imu;
private final VisionSubsystem vision;
private final SwerveDrivePoseEstimator poseEstimator;
private final TimeInterpolatableBuffer<Pose2d> poseHistory =
TimeInterpolatableBuffer.createBuffer(1.5);
private double lastAddedVisionTimestamp = 0;
private Optional<VisionResult> latestResult = Optional.empty();

public LocalizationSubsystem(ImuSubsystem imu, VisionSubsystem vision) {
super(SubsystemPriority.LOCALIZATION, LocalizationState.DEFAULT_STATE);
Expand All @@ -25,9 +31,19 @@ public LocalizationSubsystem(ImuSubsystem imu, VisionSubsystem vision) {

@Override
protected void collectInputs() {
var maybeResults = vision.getVisionResult();
if (maybeResults.isPresent()) {
var results = maybeResults.get();
latestResult = vision.getVisionResult();
}

public Pose2d getPose() {
return poseEstimator.getEstimatedPosition();
}

@Override
public void robotPeriodic() {
super.robotPeriodic();

if (latestResult.isPresent()) {
var results = latestResult.get();
Pose2d visionPose = results.pose();

double visionTimestamp = results.timestamp();
Expand All @@ -45,12 +61,7 @@ protected void collectInputs() {
lastAddedVisionTimestamp = visionTimestamp;
}
}
poseHistory.addSample(Timer.getFPGATimestamp(), poseEstimator.getEstimatedPosition());
PoseEstimate mt2Estimate = LimelightHelpers.getBotPoseEstimate_wpiBlue_MegaTag2("");
vision.setRobotPose(getPose());
}

public Pose2d getPose() {
return poseEstimator;
poseHistory.addSample(Timer.getFPGATimestamp(), poseEstimator.getEstimatedPosition());
}
}

0 comments on commit b1c8149

Please sign in to comment.