Skip to content

Commit

Permalink
[#311] - added pose data
Browse files Browse the repository at this point in the history
  • Loading branch information
HeeistHo committed Jul 2, 2023
1 parent 6941458 commit 71577a8
Show file tree
Hide file tree
Showing 4 changed files with 202 additions and 62 deletions.
94 changes: 41 additions & 53 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.subsystems;

import java.util.Optional;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;
Expand Down Expand Up @@ -64,6 +65,7 @@
import frc.thunder.shuffleboard.LightningShuffleboard;
import frc.thunder.shuffleboard.LightningShuffleboardPeriodic;

import org.photonvision.EstimatedRobotPose;
import org.photonvision.PhotonCamera;

/**
Expand Down Expand Up @@ -383,59 +385,45 @@ public void updateOdometry() {

private boolean firstTime = true;

// public void updateVision() {
// if (VisionBase.isVisionEnabled()) {
// visionPose2d = null;
// double latency = 0;
// double tagDistance = 0;
// if (frontCamera.hasVision()) {
// visionPose2d = limelightFront.getRobotPose();
// latency = limelightFront.getLatencyBotPoseBlue();
// tagDistance = limelightFront.getTagDistance();
// if (firstTime) {
// setInitialPose(visionPose2d);
// firstTime = false;
// }
// } else if (limelightBack.hasVision()) {
// visionPose2d = limelightBack.getRobotPose();
// latency = limelightBack.getLatencyBotPoseBlue();
// tagDistance = limelightBack.getTagDistance();
// if (firstTime) {
// setInitialPose(visionPose2d);

// firstTime = false;
// }
// }

// if (visionPose2d == null || visionPose2d.getX() > 23.04 || visionPose2d.getY() > 8.02 || visionPose2d.getX() < 0 || visionPose2d.getY() < 0 || tagDistance > 4) {
// return;
// }

// double currTime = Timer.getFPGATimestamp();
// LightningShuffleboard.setDouble("Drivetrain", "Velocity between points", pose.getTranslation().getDistance(visionPose2d.getTranslation()) / (currTime - lastTime));
// if (pose.getTranslation().getDistance(visionPose2d.getTranslation()) / (currTime - lastTime) > DrivetrainConstants.MAX_VELOCITY_METERS_PER_SECOND) {
// return;
// }

// // if (tagDistance != -1) {
// // double distanceBasedDev = VisionConstants.visionStandardDevMap.get(tagDistance + getDriveVelocity());
// // poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(distanceBasedDev, distanceBasedDev, distanceBasedDev));
// // }

// visionPose2d = new Pose2d(visionPose2d.getX(), pose.getY(), getHeading());
// poseEstimator.addVisionMeasurement(visionPose2d, Timer.getFPGATimestamp() - latency - .0472);
// pose = poseEstimator.getEstimatedPosition();

// lastKnownGoodVisionX = visionPose2d.getX();
// lastKnownGoodVisionY = visionPose2d.getY();
// lastKnownGoodVisionRotation = visionPose2d.getRotation().getDegrees();
// lastTime = currTime;

// LightningShuffleboard.setDouble("Drivetrain", "Accepted vision X", lastKnownGoodVisionX);
// LightningShuffleboard.setDouble("Drivetrain", "Accepted vision Y", lastKnownGoodVisionY);
// LightningShuffleboard.setDouble("Drivetrain", "Accepted vision Rotation", lastKnownGoodVisionRotation);
// }
// }
public void updateVision() {
if (VisionBase.isVisionEnabled()) {
// visionPose2d = null;
// double latency = 0;
// double tagDistance = 0;
Optional<EstimatedRobotPose> result = frontCamera.getEstimatedGlobalPose(poseEstimator.getEstimatedPosition());
if (frontCamera.hasVision()) {
EstimatedRobotPose photonPose = result.get();
visionPose2d = photonPose.estimatedPose.toPose2d();
poseEstimator.addVisionMeasurement(visionPose2d, Timer.getFPGATimestamp() - .0472); // Todo: Add Latency!
}

// if (visionPose2d == null || visionPose2d.getX() > 23.04 || visionPose2d.getY() > 8.02 || visionPose2d.getX() < 0 || visionPose2d.getY() < 0 || tagDistance > 4) {
// return;
// }

double currTime = Timer.getFPGATimestamp();
// LightningShuffleboard.setDouble("Drivetrain", "Velocity between points", pose.getTranslation().getDistance(visionPose2d.getTranslation()) / (currTime - lastTime));
// if (pose.getTranslation().getDistance(visionPose2d.getTranslation()) / (currTime - lastTime) > DrivetrainConstants.MAX_VELOCITY_METERS_PER_SECOND) {
// return;
// }

// if (tagDistance != -1) {
// double distanceBasedDev = VisionConstants.visionStandardDevMap.get(tagDistance + getDriveVelocity());
// poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(distanceBasedDev, distanceBasedDev, distanceBasedDev));
// }

pose = poseEstimator.getEstimatedPosition();

lastKnownGoodVisionX = visionPose2d.getX();
lastKnownGoodVisionY = visionPose2d.getY();
lastKnownGoodVisionRotation = visionPose2d.getRotation().getDegrees();
lastTime = currTime;

LightningShuffleboard.setDouble("Drivetrain", "Accepted vision X", lastKnownGoodVisionX);
LightningShuffleboard.setDouble("Drivetrain", "Accepted vision Y", lastKnownGoodVisionY);
LightningShuffleboard.setDouble("Drivetrain", "Accepted vision Rotation", lastKnownGoodVisionRotation);
}
}

/**
* ta
Expand Down
62 changes: 57 additions & 5 deletions src/main/java/frc/robot/subsystems/PhotonBack.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,33 @@

package frc.robot.subsystems;


import java.util.Optional;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;

import org.photonvision.EstimatedRobotPose;
import org.photonvision.PhotonCamera;
import org.photonvision.PhotonPoseEstimator;
import org.photonvision.targeting.PhotonPipelineResult;
import org.photonvision.targeting.PhotonTrackedTarget;

import edu.wpi.first.math.Pair;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.thunder.shuffleboard.LightningShuffleboardPeriodic;


public class PhotonBack extends SubsystemBase {
PhotonCamera photonCamera;
PhotonPoseEstimator photonPoseEstimator;

public String photonName;
PhotonCamera cam = new PhotonCamera(photonName);
boolean hasTarget = false;
boolean loggingStarted = false;

private LightningShuffleboardPeriodic periodicShuffleboard;

/** Creates a new PhotonBack. */
public PhotonBack(String photonName) {
Expand All @@ -26,23 +42,59 @@ public PhotonBack(String photonName) {
@Override
public void periodic() {
// This method will be called once per scheduler run
if (!loggingStarted && hasVision()){
initializeLogging();
}

if (hasVision() && loggingStarted){
periodicShuffleboard.loop();
}
}

public boolean hasVision() {
return getPipelineResult().getTargets() != null;
}

public PhotonPipelineResult getPipelineResult() {
return cam.getLatestResult();
}

public PhotonTrackedTarget getTrackedTarget() {
return getPipelineResult().getBestTarget();
}

public double getYaw(){
return getPipelineResult().getBestTarget().getYaw();
return getTrackedTarget().getYaw();
}

public double getPitch(){
return getPipelineResult().getBestTarget().getPitch();
return getTrackedTarget().getPitch();
}

public double getSkew(){
return getPipelineResult().getBestTarget().getSkew();
return getTrackedTarget().getSkew();
}

public double getTargetId(){
return getTrackedTarget().getFiducialId();
}

@SuppressWarnings("unchecked")
private void initializeLogging() {
periodicShuffleboard = new LightningShuffleboardPeriodic("Vision", 0.17,
new Pair<String, Object>(photonName + "Skew", (DoubleSupplier) () -> getSkew()),
new Pair<String, Object>(photonName + "Pitch", (DoubleSupplier) () -> getPitch()),
new Pair<String, Object>(photonName + "Yaw", (DoubleSupplier) () -> getYaw()),
new Pair<String, Object>(photonName + "TrackedTarget", (DoubleSupplier) () -> getTargetId()),
new Pair<String, Object>(photonName + "Has Vision", (BooleanSupplier) () -> hasVision()));
}

}
public Optional<EstimatedRobotPose> getEstimatedGlobalPose(Pose2d prevEstimatedRobotPose) {
if (photonPoseEstimator == null) {
// The field layout failed to load, so we cannot estimate poses.
return Optional.empty();
}
photonPoseEstimator.setReferencePose(prevEstimatedRobotPose);
return photonPoseEstimator.update();
}
}
100 changes: 100 additions & 0 deletions src/main/java/frc/robot/subsystems/PhotonFront.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.subsystems;


import java.util.Optional;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;

import org.photonvision.EstimatedRobotPose;
import org.photonvision.PhotonCamera;
import org.photonvision.PhotonPoseEstimator;
import org.photonvision.targeting.PhotonPipelineResult;
import org.photonvision.targeting.PhotonTrackedTarget;

import edu.wpi.first.math.Pair;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.thunder.shuffleboard.LightningShuffleboardPeriodic;


public class PhotonFront extends SubsystemBase {
PhotonCamera photonCamera;
PhotonPoseEstimator photonPoseEstimator;

public String photonName;
PhotonCamera cam = new PhotonCamera(photonName);
boolean loggingStarted = false;

private LightningShuffleboardPeriodic periodicShuffleboard;

/** Creates a new PhotonBack. */
public PhotonFront(String photonName) {
this.photonName = photonName;

CommandScheduler.getInstance().registerSubsystem(this);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
if (!loggingStarted && hasVision()){
initializeLogging();
}

if (hasVision() && loggingStarted){
periodicShuffleboard.loop();
}
}

public boolean hasVision() {
return getPipelineResult().getTargets() != null;
}

public PhotonPipelineResult getPipelineResult() {
return cam.getLatestResult();
}

public PhotonTrackedTarget getTrackedTarget() {
return getPipelineResult().getBestTarget();
}

public double getYaw(){
return getTrackedTarget().getYaw();
}

public double getPitch(){
return getTrackedTarget().getPitch();
}

public double getSkew(){
return getTrackedTarget().getSkew();
}

public double getTargetId(){
return getTrackedTarget().getFiducialId();
}

@SuppressWarnings("unchecked")
private void initializeLogging() {
periodicShuffleboard = new LightningShuffleboardPeriodic("Vision", 0.17,
new Pair<String, Object>(photonName + "Skew", (DoubleSupplier) () -> getSkew()),
new Pair<String, Object>(photonName + "Pitch", (DoubleSupplier) () -> getPitch()),
new Pair<String, Object>(photonName + "Yaw", (DoubleSupplier) () -> getYaw()),
new Pair<String, Object>(photonName + "TrackedTarget", (DoubleSupplier) () -> getTargetId()),
new Pair<String, Object>(photonName + "Has Vision", (BooleanSupplier) () -> hasVision()));
}

public Optional<EstimatedRobotPose> getEstimatedGlobalPose(Pose2d prevEstimatedRobotPose) {
if (photonPoseEstimator == null) {
// The field layout failed to load, so we cannot estimate poses.
return Optional.empty();
}
photonPoseEstimator.setReferencePose(prevEstimatedRobotPose);
return photonPoseEstimator.update();
}
}
8 changes: 4 additions & 4 deletions vendordeps/photonlib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "photonlib.json",
"name": "photonlib",
"version": "v2023.1.2",
"version": "v2023.4.2",
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004 ",
"mavenUrls": [
"https://maven.photonvision.org/repository/internal",
Expand All @@ -13,7 +13,7 @@
{
"groupId": "org.photonvision",
"artifactId": "PhotonLib-cpp",
"version": "v2023.1.2",
"version": "v2023.4.2",
"libName": "Photon",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -30,12 +30,12 @@
{
"groupId": "org.photonvision",
"artifactId": "PhotonLib-java",
"version": "v2023.1.2"
"version": "v2023.4.2"
},
{
"groupId": "org.photonvision",
"artifactId": "PhotonTargeting-java",
"version": "v2023.1.2"
"version": "v2023.4.2"
}
]
}

0 comments on commit 71577a8

Please sign in to comment.