Using WPILib Pose Estimation, Simulation, and PhotonVision Together
The following example comes from the PhotonLib example repository (Java). Full code is available at that links.
Knowledge and Equipment Needed
Everything required in Combining Aiming and Getting in Range, plus some familiarity with WPILib pose estimation functionality.
Background
This example builds upon WPILib’s Differential Drive Pose Estimator. It adds a PhotonCamera
to gather estimates of the robot’s position on the field. This in turn can be used for aligning with vision targets, and increasing accuracy of autonomous routines.
To support simulation, a SimVisionSystem
is used to drive data into the PhotonCamera
. The far high goal target from 2020 is modeled.
Walkthrough
WPILib’s Pose2d
class is used to represent robot positions on the field.
Three different Pose2d
positions are relevant for this example:
Desired Pose: The location the some autonomous routine wants the robot to be in.
Estimated Pose: The location the software believes the robot to be in, based on physics models and sensor feedback.
Actual Pose: The locations he robot is actually at. The physics simulation generates this in simulation, but it cannot be directly measured on the real robot.
Estimating Pose
The DrivetrainPoseEstimator
class is responsible for generating an estimated robot pose using sensor readings (including PhotonVision).
Please reference the WPILib documentation on using the DifferentialDrivePoseEstimator
class.
For both simulation and on-robot code, we create objects to represent the physical location and size of the vision targets we are calibrated to detect. This example models the down-field high goal vision target from the 2020 and 2021 games.
79 // See
80 // https://firstfrc.blob.core.windows.net/frc2020/PlayingField/2020FieldDrawing-SeasonSpecific.pdf
81 // page 208
82 public static final double targetWidth =
83 Units.inchesToMeters(41.30) - Units.inchesToMeters(6.70); // meters
84
85 // See
86 // https://firstfrc.blob.core.windows.net/frc2020/PlayingField/2020FieldDrawing-SeasonSpecific.pdf
87 // page 197
88 public static final double targetHeight =
89 Units.inchesToMeters(98.19) - Units.inchesToMeters(81.19); // meters
90 public static final double targetHeightAboveGround = Units.inchesToMeters(81.19); // meters
91
92 // See https://firstfrc.blob.core.windows.net/frc2020/PlayingField/LayoutandMarkingDiagram.pdf
93 // pages 4 and 5
94 public static final double kFarTgtXPos = Units.feetToMeters(54);
95 public static final double kFarTgtYPos =
96 Units.feetToMeters(27 / 2) - Units.inchesToMeters(43.75) - Units.inchesToMeters(48.0 / 2.0);
97 public static final Pose2d kFarTargetPose =
98 new Pose2d(new Translation2d(kFarTgtXPos, kFarTgtYPos), new Rotation2d(0.0));
99
100 public static final SimVisionTarget kFarTarget =
101 new SimVisionTarget(kFarTargetPose, targetHeightAboveGround, targetWidth, targetHeight);
//Coming soon!
To incorporate Photon Vision, we need to create a PhotonCamera
:
49 private PhotonCamera cam = new PhotonCamera(Constants.kCamName);
//Coming soon!
During periodic execution, we read back camera results. If we see a target in the image, we pass the camera-measured pose of the robot to the DifferentialDrivePoseEstimator
.
82 public void update(
83 DifferentialDriveWheelSpeeds actWheelSpeeds, double leftDist, double rightDist) {
84 m_poseEstimator.update(gyro.getRotation2d(), actWheelSpeeds, leftDist, rightDist);
85
86 var res = cam.getLatestResult();
87 if (res.hasTargets()) {
88 double imageCaptureTime = Timer.getFPGATimestamp() - res.getLatencyMillis();
89 Transform2d camToTargetTrans = res.getBestTarget().getCameraToTarget();
90 Pose2d camPose = Constants.kFarTargetPose.transformBy(camToTargetTrans.inverse());
91 m_poseEstimator.addVisionMeasurement(
92 camPose.transformBy(Constants.kCameraToRobot), imageCaptureTime);
93 }
94 }
//Coming soon!
That’s it!
Simulating the Camera
First, we create a new SimVisionSystem
to represent our camera and coprocessor running PhotonVision.
77 // Simulated Vision System.
78 // Configure these to match your PhotonVision Camera,
79 // pipeline, and LED setup.
80 double camDiagFOV = 75.0; // degrees
81 double camPitch = 15.0; // degrees
82 double camHeightOffGround = 0.85; // meters
83 double maxLEDRange = 20; // meters
84 int camResolutionWidth = 640; // pixels
85 int camResolutionHeight = 480; // pixels
86 double minTargetArea = 10; // square pixels
87
88 SimVisionSystem simVision =
89 new SimVisionSystem(
90 Constants.kCamName,
91 camDiagFOV,
92 camPitch,
93 Constants.kCameraToRobot,
94 camHeightOffGround,
95 maxLEDRange,
96 camResolutionWidth,
97 camResolutionHeight,
98 minTargetArea);
//Coming soon!
Then, we add our target to the simulated vision system.
100 public DrivetrainSim() {
101 simVision.addSimVisionTarget(Constants.kFarTarget);
102 }
//Coming soon!
If you have additional targets you want to detect, you can add them in the same way as the first one.
Updating the Simulated Vision System
Once we have all the properties of our simulated vision system defined, the remaining work is minimal. Periodically, pass in the robot’s pose to the simulated vision system.
141 // Update PhotonVision based on our new robot position.
142 simVision.processFrame(drivetrainSimulator.getPose());
//Coming soon!
The rest is done behind the scenes.