mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
RobotPoseEstimator Enhancements (#677)
* Use List for RobotPoseEstimator constructor * Update `RobotPoseEstimator` constructor to accept wpilib `AprilTagFieldLayout` java * Initial cpp changes * Java return optional from update * Fix java test * Clean up strategy switch * small lint * Actually link to vision_shared * Fix auto optimized imports * format * report error * small method changes * format and clean up Co-authored-by: Matt <matthew.morley.ca@gmail.com>
This commit is contained in:
@@ -27,7 +27,6 @@ package org.photonvision;
|
||||
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.geometry.Rotation3d;
|
||||
import edu.wpi.first.math.geometry.Transform3d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.geometry.Translation3d;
|
||||
@@ -139,13 +138,7 @@ public class SimVisionSystem {
|
||||
* PhotonVision parameters.
|
||||
*/
|
||||
public void processFrame(Pose2d robotPoseMeters) {
|
||||
var robotPose3d =
|
||||
new Pose3d(
|
||||
robotPoseMeters.getX(),
|
||||
robotPoseMeters.getY(),
|
||||
0.0,
|
||||
new Rotation3d(0, 0, robotPoseMeters.getRotation().getRadians()));
|
||||
processFrame(robotPose3d);
|
||||
processFrame(new Pose3d(robotPoseMeters));
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
Reference in New Issue
Block a user