Skip to content
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
6 changes: 5 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.robot.util.sim.PhysicsSim;
import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
Expand Down Expand Up @@ -135,5 +136,8 @@ public void simulationInit() {}

/** This function is called periodically whilst in simulation. */
@Override
public void simulationPeriodic() {}
public void simulationPeriodic() {
PhysicsSim.getInstance().run();
robotContainer.updateVisionSim();
}
}
42 changes: 26 additions & 16 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,13 @@

import com.pathplanner.lib.auto.AutoBuilder;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.commands.DriveCommands;
import frc.robot.generated.TunerConstants;
Expand All @@ -26,11 +25,10 @@
import frc.robot.subsystems.drive.ModuleIO;
import frc.robot.subsystems.drive.ModuleIOSim;
import frc.robot.subsystems.drive.ModuleIOTalonFX;
import frc.robot.subsystems.intakeFeederwheel.IntakeFeederwheelIO;
import frc.robot.subsystems.intakeFeederwheel.IntakeFeederwheelSubsystem;
import frc.robot.subsystems.intakeFeederwheel.IntakeFeederwheelTalonFX;
import frc.robot.subsystems.flywheel.FlywheelIO;
import frc.robot.subsystems.flywheel.FlywheelIOTalonFX;
import frc.robot.subsystems.vision.*;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

/**
Expand All @@ -42,15 +40,22 @@
public class RobotContainer {
// Subsystems
private final Drive drive;
private IntakeFeederwheelSubsystem intakeFeederwheel;
private final FlywheelIO flywheel;
private final Vision vision;

// Controller
private final CommandXboxController controller = new CommandXboxController(0);

// Dashboard inputs
private final LoggedDashboardChooser<Command> autoChooser;

public void updateVisionSim() {
Pose3d frontCameraPose =
new Pose3d(drive.getPose()).transformBy(VisionConstants.frontCamTrans);

Logger.recordOutput("Front Cam Transform", frontCameraPose);
}

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
switch (Constants.currentMode) {
Expand Down Expand Up @@ -80,8 +85,9 @@ public RobotContainer() {
// new ModuleIOTalonFXS(TunerConstants.FrontRight),
// new ModuleIOTalonFXS(TunerConstants.BackLeft),
// new ModuleIOTalonFXS(TunerConstants.BackRight));

intakeFeederwheel = new IntakeFeederwheelSubsystem(new IntakeFeederwheelTalonFX());
vision =
new Vision(
drive, new VisionIOLimelight("Front Camera", drive::getRotation));

flywheel = new FlywheelIOTalonFX();
break;
Expand All @@ -96,9 +102,15 @@ public RobotContainer() {
new ModuleIOSim(TunerConstants.BackLeft),
new ModuleIOSim(TunerConstants.BackRight));

intakeFeederwheel = new IntakeFeederwheelSubsystem(new IntakeFeederwheelTalonFX());

flywheel = new FlywheelIOTalonFX();
vision =
new Vision(
drive,
new VisionIOPhotonVisionSim(
"Front Camera",
VisionConstants.frontCamTrans,
drive::getPose));

break;

default:
Expand All @@ -111,8 +123,7 @@ public RobotContainer() {
new ModuleIO() {},
new ModuleIO() {});

intakeFeederwheel = new IntakeFeederwheelSubsystem(new IntakeFeederwheelIO() {});

vision = new Vision(drive, new VisionIO() {});
flywheel = new FlywheelIO() {};
break;
}
Expand Down Expand Up @@ -146,8 +157,9 @@ public RobotContainer() {

/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link Joystick} or {@link
* XboxController}), and then passing it to a {@link JoystickButton}.
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
private void configureButtonBindings() {
// Default command, normal field-relative drive
Expand Down Expand Up @@ -183,8 +195,6 @@ private void configureButtonBindings() {
Rotation2d.kZero)),
drive)
.ignoringDisable(true));

controller.rightTrigger().onTrue(intakeFeederwheel.rollIn());
controller.leftTrigger().whileTrue(Commands.run(() -> flywheel.setRoller(1)));
}

Expand Down
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,14 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.generated.TunerConstants;
import frc.robot.subsystems.vision.Vision;
import frc.robot.util.LocalADStarAK;
import java.util.concurrent.locks.Lock;
import java.util.concurrent.locks.ReentrantLock;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Drive extends SubsystemBase {
public class Drive extends SubsystemBase implements Vision.VisionConsumer {
// TunerConstants doesn't include these constants, so they are declared locally
static final double ODOMETRY_FREQUENCY =
new CANBus(TunerConstants.DrivetrainConstants.CANBusName).isNetworkFD() ? 250.0 : 100.0;
Expand Down Expand Up @@ -373,4 +374,13 @@ public static Translation2d[] getModuleTranslations() {
TunerConstants.BackRight.LocationX, TunerConstants.BackRight.LocationY)
};
}

@Override
public void accept(
Pose2d visionRobotPoseMeters,
double timestampSeconds,
Matrix<N3, N1> visionMeasurementStdDevs) {
poseEstimator.addVisionMeasurement(
visionRobotPoseMeters, timestampSeconds, visionMeasurementStdDevs);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import com.ctre.phoenix6.controls.Follower;
import com.ctre.phoenix6.controls.MotionMagicVelocityVoltage;
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.TalonFX;
import frc.robot.Robot;
import frc.robot.util.sim.PhysicsSim;
Expand Down
156 changes: 156 additions & 0 deletions src/main/java/frc/robot/subsystems/vision/Vision.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,156 @@
package frc.robot.subsystems.vision;

import static frc.robot.subsystems.vision.VisionConstants.*;

import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.subsystems.vision.VisionIO.PoseObservationType;
import java.util.LinkedList;
import java.util.List;
import org.littletonrobotics.junction.Logger;

public class Vision extends SubsystemBase {
private final VisionConsumer consumer;
private final VisionIO[] io;
private final VisionIOInputsAutoLogged[] inputs;
private final Alert[] disconnectedAlerts;

public Vision(VisionConsumer consumer, VisionIO... io) {
this.consumer = consumer;
this.io = io;

this.inputs = new VisionIOInputsAutoLogged[io.length];
for (int i = 0; i < inputs.length; i++) {
inputs[i] = new VisionIOInputsAutoLogged();
}

this.disconnectedAlerts = new Alert[io.length];
for (int i = 0; i < inputs.length; i++) {
disconnectedAlerts[i] =
new Alert(
"Vision camera " + Integer.toString(i) + " is disconnected.",
AlertType.kWarning);
}
}

public Rotation2d getTargetX(int cameraIndex) {
return inputs[cameraIndex].latestTargetObservation.tx();
}

@Override
public void periodic() {
for (int i = 0; i < io.length; i++) {
io[i].updateInputs(inputs[i]);
Logger.processInputs("Vision/Camera" + Integer.toString(i), inputs[i]);
}

List<Pose3d> allTagPoses = new LinkedList<>();
List<Pose3d> allRobotPoses = new LinkedList<>();
List<Pose3d> allRobotPosesAccepted = new LinkedList<>();
List<Pose3d> allRobotPosesRejected = new LinkedList<>();

for (int cameraIndex = 0; cameraIndex < io.length; cameraIndex++) {
disconnectedAlerts[cameraIndex].set(!inputs[cameraIndex].connected);

List<Pose3d> tagPoses = new LinkedList<>();
List<Pose3d> robotPoses = new LinkedList<>();
List<Pose3d> robotPosesAccepted = new LinkedList<>();
List<Pose3d> robotPosesRejected = new LinkedList<>();

for (int tagId : inputs[cameraIndex].tagIds) {
var tagPose = aprilTagLayout.getTagPose(tagId);
if (tagPose.isPresent()) {
tagPoses.add(tagPose.get());
}
}

for (var observation : inputs[cameraIndex].poseObservations) {
boolean rejectPose =
observation.tagCount() == 0 // Must have at least one tag
|| (observation.tagCount() == 1
&& observation.ambiguity()
> maxAmbiguity) // Cannot be high ambiguity
|| Math.abs(observation.pose().getZ())
> maxZError // Must have realistic Z coordinate
|| observation.pose().getX() < 0.0
|| observation.pose().getX() > aprilTagLayout.getFieldLength()
|| observation.pose().getY() < 0.0
|| observation.pose().getY() > aprilTagLayout.getFieldWidth();

robotPoses.add(observation.pose());
if (rejectPose) {
robotPosesRejected.add(observation.pose());
} else {
robotPosesAccepted.add(observation.pose());
}

if (rejectPose) {
continue;
}

double stdDevFactor =
Math.pow(observation.averageTagDistance(), 2.0) / observation.tagCount();
double linearStdDev = linearStdDevBaseline * stdDevFactor;
double angularStdDev = angularStdDevBaseline * stdDevFactor;
if (observation.type() == PoseObservationType.MEGATAG_2) {
linearStdDev *= linearStdDevMegatag2Factor;
angularStdDev *= angularStdDevMegatag2Factor;
}
if (cameraIndex < cameraStdDevFactors.length) {
linearStdDev *= cameraStdDevFactors[cameraIndex];
angularStdDev *= cameraStdDevFactors[cameraIndex];
}

consumer.accept(
observation.pose().toPose2d(),
observation.timestamp(),
VecBuilder.fill(linearStdDev, linearStdDev, angularStdDev));
}

Logger.recordOutput(
"Vision/Camera" + Integer.toString(cameraIndex) + "/TagPoses",
tagPoses.toArray(new Pose3d[tagPoses.size()]));
Logger.recordOutput(
"Vision/Camera" + Integer.toString(cameraIndex) + "/RobotPoses",
robotPoses.toArray(new Pose3d[robotPoses.size()]));
Logger.recordOutput(
"Vision/Camera" + Integer.toString(cameraIndex) + "/RobotPosesAccepted",
robotPosesAccepted.toArray(new Pose3d[robotPosesAccepted.size()]));
Logger.recordOutput(
"Vision/Camera" + Integer.toString(cameraIndex) + "/RobotPosesRejected",
robotPosesRejected.toArray(new Pose3d[robotPosesRejected.size()]));
allTagPoses.addAll(tagPoses);
allRobotPoses.addAll(robotPoses);
allRobotPosesAccepted.addAll(robotPosesAccepted);
allRobotPosesRejected.addAll(robotPosesRejected);
}

Logger.recordOutput(
"Vision/Summary/TagPoses", allTagPoses.toArray(new Pose3d[allTagPoses.size()]));
Logger.recordOutput(
"Vision/Summary/RobotPoses",
allRobotPoses.toArray(new Pose3d[allRobotPoses.size()]));
Logger.recordOutput(
"Vision/Summary/RobotPosesAccepted",
allRobotPosesAccepted.toArray(new Pose3d[allRobotPosesAccepted.size()]));
Logger.recordOutput(
"Vision/Summary/RobotPosesRejected",
allRobotPosesRejected.toArray(new Pose3d[allRobotPosesRejected.size()]));
}

@FunctionalInterface
public interface VisionConsumer {
void accept(
Pose2d visionRobotPoseMeters,
double timestampSeconds,
Matrix<N3, N1> visionMeasurementStdDevs);
}
}
33 changes: 33 additions & 0 deletions src/main/java/frc/robot/subsystems/vision/VisionConstants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
package frc.robot.subsystems.vision;

import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;

public class VisionConstants {
public static AprilTagFieldLayout aprilTagLayout =
AprilTagFieldLayout.loadField(AprilTagFields.k2024Crescendo);


Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

delete this if it's not being used

public static double maxAmbiguity = 0.3;
public static double maxZError = 0.75;

public static double linearStdDevBaseline = 0.02; // Meters
public static double angularStdDevBaseline = 0.06; // Radians

public static double[] cameraStdDevFactors = new double[] {1.0, 1.0};

public static double linearStdDevMegatag2Factor = 0.5;
public static double angularStdDevMegatag2Factor = Double.POSITIVE_INFINITY;

public static Transform3d frontCamTrans =
new Transform3d(
new Translation3d(
Units.inchesToMeters(17),
Units.inchesToMeters(0),
Units.inchesToMeters(21)),
new Rotation3d(0, Math.toRadians(180), Math.toRadians(180)));
}
34 changes: 34 additions & 0 deletions src/main/java/frc/robot/subsystems/vision/VisionIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
package frc.robot.subsystems.vision;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import org.littletonrobotics.junction.AutoLog;

public interface VisionIO {
@AutoLog
class VisionIOInputs {
public boolean connected = false;
public TargetObservation latestTargetObservation =
new TargetObservation(new Rotation2d(), new Rotation2d());
public PoseObservation[] poseObservations = new PoseObservation[0];
public int[] tagIds = new int[0];
}

record TargetObservation(Rotation2d tx, Rotation2d ty) {}

record PoseObservation(
double timestamp,
Pose3d pose,
double ambiguity,
int tagCount,
double averageTagDistance,
PoseObservationType type) {}

enum PoseObservationType {
MEGATAG_1,
MEGATAG_2,
PHOTONVISION
}

default void updateInputs(VisionIOInputs inputs) {}
}
Loading
Loading