global pose vision transformations

This commit is contained in:
Tylr-J42 2025-02-15 02:48:28 -05:00
parent 38dad2861d
commit 9cc9b993eb

View File

@ -1,13 +1,23 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.networktables.BooleanSubscriber; import edu.wpi.first.networktables.BooleanSubscriber;
import edu.wpi.first.networktables.DoubleSubscriber; import edu.wpi.first.networktables.DoubleSubscriber;
import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.networktables.NetworkTableInstance;
import frc.robot.constants.VisionConstants;
public class Vision{ public class Vision{
private DoubleSubscriber blackRobotRelativePose; private DoubleSubscriber blackRobotRelativeX;
private DoubleSubscriber blackRobotRelativeY;
private DoubleSubscriber blackRobotRelativeZ;
private DoubleSubscriber blackClosestTag; private DoubleSubscriber blackClosestTag;
private BooleanSubscriber blackTagDetected; private BooleanSubscriber blackTagDetected;
@ -22,13 +32,18 @@ public class Vision{
private DoubleSubscriber orangeFramerate; private DoubleSubscriber orangeFramerate;
public Vision(){ private DoubleSupplier gyroAngle;
public Vision(DoubleSupplier gyroAngle){
NetworkTableInstance inst = NetworkTableInstance.getDefault(); NetworkTableInstance inst = NetworkTableInstance.getDefault();
NetworkTable blackVisionTable = inst.getTable("black_Fiducial"); NetworkTable blackVisionTable = inst.getTable("black_Fiducial");
NetworkTable orangeVisionTable = inst.getTable("orange_Fiducial"); NetworkTable orangeVisionTable = inst.getTable("orange_Fiducial");
blackRobotRelativePose = blackVisionTable.getDoubleTopic("blackRelativePose").subscribe(0.0); blackRobotRelativeX = orangeVisionTable.getDoubleTopic("blackRelativeX").subscribe(0.0);
blackRobotRelativeY = orangeVisionTable.getDoubleTopic("blackRelativeY").subscribe(0.0);
blackRobotRelativeZ = orangeVisionTable.getDoubleTopic("blackRelativeZ").subscribe(0.0);
blackClosestTag = blackVisionTable.getDoubleTopic("blackClosestTag").subscribe(0.0); blackClosestTag = blackVisionTable.getDoubleTopic("blackClosestTag").subscribe(0.0);
blackTagDetected = blackVisionTable.getBooleanTopic("blackTagDetected").subscribe(false); blackTagDetected = blackVisionTable.getBooleanTopic("blackTagDetected").subscribe(false);
@ -44,16 +59,45 @@ public class Vision{
orangeFramerate = orangeVisionTable.getDoubleTopic("orangeFPS").subscribe(0.0); orangeFramerate = orangeVisionTable.getDoubleTopic("orangeFPS").subscribe(0.0);
} }
public double getBlackGlobalPose(){ public Pose2d relativeToGlobalPose2d(int tagID, Translation2d relativeCoords, Rotation2d gyroAngle){
return blackRobotRelativePose.get(); Pose2d tag2dPose = new Pose2d(VisionConstants.globalTagCoords[tagID][0],
VisionConstants.globalTagCoords[tagID][1],
new Rotation2d());
Pose2d relative = new Pose2d(relativeCoords, gyroAngle);
Transform2d relative2dTransformation = new Transform2d(relative.getTranslation(), relative.getRotation());
Pose2d globalPose = tag2dPose.transformBy(relative2dTransformation.inverse());
return new Pose2d(globalPose.getTranslation(), gyroAngle);
} }
public double getBlackClosestTag(){ public Pose2d getBlackGlobalPose(){
return blackClosestTag.get();
return relativeToGlobalPose2d(getBlackClosestTag(),
new Translation2d(getBlackRelativeX(), getBlackRelativeY()),
new Rotation2d(gyroAngle.getAsDouble()));
}
public double getBlackRelativeX(){
return blackRobotRelativeX.get();
}
public double getBlackRelativeY(){
return blackRobotRelativeY.get();
}
public double getBlackRelativeZ(){
return blackRobotRelativeZ.get();
}
public int getBlackClosestTag(){
return (int) blackClosestTag.get();
} }
public double getBlackTimeStamp(){ public double getBlackTimeStamp(){
return blackRobotRelativePose.getLastChange(); return blackRobotRelativeX.getLastChange();
} }
public boolean getBlackTagDetected(){ public boolean getBlackTagDetected(){
@ -64,12 +108,27 @@ public class Vision{
return blackFramerate.get(); return blackFramerate.get();
} }
public double getOrangeGlobalX(){ public Pose2d getOrangeGlobalPose(){
return relativeToGlobalPose2d(getBlackClosestTag(),
new Translation2d(getBlackRelativeX(), getBlackRelativeY()),
new Rotation2d(gyroAngle.getAsDouble()));
}
public double getOrangeRelativeX(){
return orangeRobotRelativeX.get(); return orangeRobotRelativeX.get();
} }
public double getOrangeClosestTag(){ public double getOrangeRelativeY(){
return orangeClosestTag.get(); return orangeRobotRelativeY.get();
}
public double getOrangeRelativeZ(){
return orangeRobotRelativeZ.get();
}
public int getOrangeClosestTag(){
return (int) orangeClosestTag.get();
} }
public double getOrangeTimeStamp(){ public double getOrangeTimeStamp(){