Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update LimelightLib, use better latency compensation for gyro measurements #55

Merged
merged 6 commits into from
Sep 27, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 0 additions & 3 deletions src/main/java/org/team1540/robot2024/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -106,9 +106,6 @@ public void robotInit() {
PathfindingCommand.warmupCommand().schedule();

AprilTagsCrescendo.getInstance().getTag(1);

// Init driver cam
LimelightHelpers.setCameraMode_Driver("limelight-driver");
}

/**
Expand Down
6 changes: 4 additions & 2 deletions src/main/java/org/team1540/robot2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@

import java.util.function.BooleanSupplier;

import static org.team1540.robot2024.Constants.SwerveConfig;
import static org.team1540.robot2024.Constants.isTuningMode;

public class RobotContainer {
Expand All @@ -62,6 +61,8 @@ public class RobotContainer {

public final PhoenixTimeSyncSignalRefresher odometrySignalRefresher = new PhoenixTimeSyncSignalRefresher(SwerveConfig.CAN_BUS);



public boolean isBrakeMode;
/**
* The container for the robot. Contains subsystems, IO devices, and commands.
Expand All @@ -80,7 +81,8 @@ public RobotContainer() {
aprilTagVision = AprilTagVision.createReal(
drivetrain::addVisionMeasurement,
elevator::getPosition,
drivetrain::getRotation);
drivetrain::getRotation,
drivetrain::getAngularVelocityRadPerSec);
noteVision = NoteVision.createReal();
} else {
elevator = Elevator.createDummy();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.team1540.robot2024.subsystems.drive;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.commands.FollowPathHolonomic;
import com.pathplanner.lib.controllers.PPHolonomicDriveController;
import com.pathplanner.lib.pathfinding.Pathfinding;
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
Expand Down Expand Up @@ -192,7 +191,6 @@ public void periodic() {
// Update odometry
poseEstimator.update(rawGyroRotation, getModulePositions());
visionPoseEstimator.update(rawGyroRotation, getModulePositions());

}

/**
Expand Down Expand Up @@ -285,6 +283,7 @@ public double getCharacterizationVelocity() {
}
return driveVelocityAverage / 4.0;
}

@AutoLogOutput(key = "Odometry/ChassisSpeeds")
public ChassisSpeeds getChassisSpeeds() {
return kinematics.toChassisSpeeds(getModuleStates());
Expand Down Expand Up @@ -331,6 +330,10 @@ public Rotation2d getRawGyroRotation() {
return rawGyroRotation;
}

public double getAngularVelocityRadPerSec() {
return gyroInputs.yawVelocityRadPerSec;
}

public void zeroFieldOrientationManual() {
fieldOrientationOffset = rawGyroRotation;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import org.team1540.robot2024.util.vision.EstimatedVisionPose;

import java.util.function.Consumer;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;

import static org.team1540.robot2024.Constants.Vision.AprilTag.*;
Expand Down Expand Up @@ -47,13 +48,15 @@ private AprilTagVision(

public static AprilTagVision createReal(Consumer<EstimatedVisionPose> visionPoseConsumer,
Supplier<Double> elevatorHeightSupplierMeters,
Supplier<Rotation2d> headingSupplier) {
Supplier<Rotation2d> headingSupplier,
DoubleSupplier headingVelocitySupplierRadPerSec) {
if (Constants.currentMode != Constants.Mode.REAL) {
DriverStation.reportWarning("Using real vision on simulated robot", false);
}
return new AprilTagVision(
new AprilTagVisionIOPhoton(FRONT_CAMERA_NAME, FRONT_CAMERA_POSE),
new AprilTagVisionIOMegaTag2(REAR_CAMERA_NAME, REAR_CAMERA_POSE, headingSupplier),
new AprilTagVisionIOMegaTag2(
REAR_CAMERA_NAME, REAR_CAMERA_POSE, headingSupplier, headingVelocitySupplierRadPerSec),
visionPoseConsumer,
elevatorHeightSupplierMeters);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ public class AprilTagVisionIOLimelight implements AprilTagVisionIO {

public AprilTagVisionIOLimelight(String name, Pose3d cameraOffsetMeters) {
this.name = name;
LimelightHelpers.setCameraMode_Processor(name);
LimelightHelpers.setLEDMode_PipelineControl(name);
setPoseOffset(cameraOffsetMeters);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,23 +6,32 @@
import org.team1540.robot2024.util.vision.LimelightHelpers;

import java.util.Arrays;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;

public class AprilTagVisionIOMegaTag2 implements AprilTagVisionIO {
private final String name;
private final Supplier<Rotation2d> heading;
private final DoubleSupplier headingVelocityRadPerSec;

public AprilTagVisionIOMegaTag2(String name, Pose3d cameraOffsetMeters, Supplier<Rotation2d> heading) {
public AprilTagVisionIOMegaTag2(String name,
Pose3d cameraOffsetMeters,
Supplier<Rotation2d> heading,
DoubleSupplier headingVelocityRadPerSec) {
this.name = name;
this.heading = heading;
LimelightHelpers.setCameraMode_Processor(name);
this.headingVelocityRadPerSec = headingVelocityRadPerSec;
LimelightHelpers.setLEDMode_PipelineControl(name);
setPoseOffset(cameraOffsetMeters);
}

@Override
public void updateInputs(AprilTagVisionIOInputs inputs) {
LimelightHelpers.SetRobotOrientation(name, heading.get().getDegrees(), 0, 0, 0, 0, 0);
LimelightHelpers.SetRobotOrientation(
name,
heading.get().getDegrees(),
Math.toDegrees(headingVelocityRadPerSec.getAsDouble()),
0, 0, 0, 0);
LimelightHelpers.PoseEstimate measurement =
DriverStation.isDisabled()
? LimelightHelpers.getBotPoseEstimate_wpiBlue(name)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ public class NoteVisionIOLimelight implements NoteVisionIO {

public NoteVisionIOLimelight(String name) {
this.name = name;
LimelightHelpers.setCameraMode_Processor(name);
LimelightHelpers.setLEDMode_PipelineControl(name);
LimelightHelpers.setPipelineIndex(name, PIPELINE_INDEX);
}
Expand Down
Loading
Loading