Skip to content
This repository was archived by the owner on Jan 4, 2024. It is now read-only.

PhotonPoseEstimator: Patch to take shared_ptr #14

Closed
wants to merge 4 commits into from
Closed
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
1 change: 1 addition & 0 deletions gen/RobotPoseEstimator.yml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ extra_includes:

enums:
PoseStrategy:
ignore: true # duplicated in PhotonPoseEstimator.h
classes:
RobotPoseEstimator:
force_type_casters:
Expand Down
2 changes: 2 additions & 0 deletions photonvision/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
Packet,
PhotonCamera,
PhotonPipelineResult,
PhotonPoseEstimator,
PhotonTrackedTarget,
PhotonUtils,
PoseStrategy,
Expand All @@ -21,6 +22,7 @@
"Packet",
"PhotonCamera",
"PhotonPipelineResult",
"PhotonPoseEstimator",
"PhotonTrackedTarget",
"PhotonUtils",
"PoseStrategy",
Expand Down
54 changes: 54 additions & 0 deletions photonvision/src/headers.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
From bb4a45a6ce4f7e7f63eeed410cbdc4ed927586df Mon Sep 17 00:00:00 2001
From: David Vo <auscompgeek@users.noreply.github.com>
Date: Mon, 30 Jan 2023 16:23:39 +1100
Subject: [PATCH] PhotonPoseEstimator: Take shared_ptr<PhotonCamera>

---
photonlib/PhotonPoseEstimator.h | 11 ++++++-----
1 file changed, 6 insertions(+), 5 deletions(-)

diff --git a/photonlib/PhotonPoseEstimator.h b/photonlib/PhotonPoseEstimator.h
index 16e18b9ae8b7..7a85538daa3e 100644
--- a/photonlib/PhotonPoseEstimator.h
+++ b/photonlib/PhotonPoseEstimator.h
@@ -79,13 +79,14 @@ class PhotonPoseEstimator {
* @param strategy The strategy it should use to determine the best pose.
* @param camera PhotonCameras and
* @param robotToCamera Transform3d from the center of the robot to the camera
* mount positions (ie, robot ➔ camera).
*/
- explicit PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags,
- PoseStrategy strategy, PhotonCamera&& camera,
- frc::Transform3d robotToCamera);
+ PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags,
+ PoseStrategy strategy,
+ std::shared_ptr<PhotonCamera> camera,
+ frc::Transform3d robotToCamera);

/**
* Get the AprilTagFieldLayout being used by the PositionEstimator.
*
* @return the AprilTagFieldLayout
@@ -135,17 +136,17 @@ class PhotonPoseEstimator {
* Update the pose estimator. Internally grabs a new PhotonPipelineResult from
* the camera and process it.
*/
std::optional<EstimatedRobotPose> Update();

- inline PhotonCamera& GetCamera() { return camera; }
+ inline std::shared_ptr<PhotonCamera> GetCamera() { return camera; }

private:
frc::AprilTagFieldLayout aprilTags;
PoseStrategy strategy;

- PhotonCamera camera;
+ std::shared_ptr<PhotonCamera> camera;
frc::Transform3d m_robotToCamera;

frc::Pose3d lastPose;
frc::Pose3d referencePose;

--
2.39.1

41 changes: 41 additions & 0 deletions photonvision/src/sources.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
From bb4a45a6ce4f7e7f63eeed410cbdc4ed927586df Mon Sep 17 00:00:00 2001
From: David Vo <auscompgeek@users.noreply.github.com>
Date: Mon, 30 Jan 2023 16:23:39 +1100
Subject: [PATCH] PhotonPoseEstimator: Take shared_ptr<PhotonCamera>

---
photonlib/PhotonPoseEstimator.cpp | 5 +++--
1 file changed, 3 insertions(+), 2 deletions(-)

diff --git a/photonlib/PhotonPoseEstimator.cpp b/photonlib/PhotonPoseEstimator.cpp
index 3b4f27807371..272e41c50672 100644
--- a/photonlib/PhotonPoseEstimator.cpp
+++ b/photonlib/PhotonPoseEstimator.cpp
@@ -42,21 +42,22 @@
#include "photonlib/PhotonPipelineResult.h"
#include "photonlib/PhotonTrackedTarget.h"

namespace photonlib {
PhotonPoseEstimator::PhotonPoseEstimator(frc::AprilTagFieldLayout tags,
- PoseStrategy strat, PhotonCamera&& cam,
+ PoseStrategy strat,
+ std::shared_ptr<PhotonCamera> cam,
frc::Transform3d robotToCamera)
: aprilTags(tags),
strategy(strat),
camera(std::move(cam)),
m_robotToCamera(robotToCamera),
lastPose(frc::Pose3d()),
referencePose(frc::Pose3d()) {}

std::optional<EstimatedRobotPose> PhotonPoseEstimator::Update() {
- auto result = camera.GetLatestResult();
+ auto result = camera->GetLatestResult();

if (!result.HasTargets()) {
return std::nullopt;
}

--
2.39.1

20 changes: 16 additions & 4 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -24,19 +24,31 @@ install_requires = [
[tool.robotpy-build]
base_package = "photonvision"

[tool.robotpy-build.static_libs."photonlib".maven_lib_download]
[tool.robotpy-build.wrappers."photonvision".maven_lib_download]
artifact_id = "PhotonLib-cpp"
group_id = "org.photonvision"
repo_url = "https://maven.photonvision.org/repository/internal"
version = "v2023.3.0"

libs = ["Photon"]
use_sources = true
sources = [
"photonlib/PhotonCamera.cpp",
"photonlib/PhotonPipelineResult.cpp",
"photonlib/PhotonPoseEstimator.cpp",
"photonlib/PhotonTrackedTarget.cpp",
"photonlib/RobotPoseEstimator.cpp",
]

[[tool.robotpy-build.wrappers."photonvision".maven_lib_download.patches]]
patch = "photonvision/src/sources.patch"

[[tool.robotpy-build.wrappers."photonvision".maven_lib_download.header_patches]]
patch = "photonvision/src/headers.patch"

[tool.robotpy-build.wrappers."photonvision"]
name = "photonvision"

depends = [
"photonlib",
"apriltag",
"wpilibc",
"wpimath_geometry",
Expand All @@ -57,7 +69,7 @@ generation_data = "gen"
Packet = "photonlib/Packet.h"
PhotonCamera = "photonlib/PhotonCamera.h"
PhotonPipelineResult = "photonlib/PhotonPipelineResult.h"
#PhotonPoseEstimator = "photonlib/PhotonPoseEstimator.h"
PhotonPoseEstimator = "photonlib/PhotonPoseEstimator.h"
PhotonTargetSortMode = "photonlib/PhotonTargetSortMode.h"
PhotonTrackedTarget = "photonlib/PhotonTrackedTarget.h"
PhotonUtils = "photonlib/PhotonUtils.h"
Expand Down
45 changes: 45 additions & 0 deletions tests/test_pose_estimator.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
import robotpy_apriltag
from wpimath.geometry import Transform3d

import photonvision


def test_photon_pose_estimator_ctor():
camera = photonvision.PhotonCamera("test_ctor")
assert camera._path
estimator = photonvision.PhotonPoseEstimator(
robotpy_apriltag.loadAprilTagLayoutField(
robotpy_apriltag.AprilTagField.k2023ChargedUp
),
photonvision.PoseStrategy.AVERAGE_BEST_TARGETS,
camera,
Transform3d(),
)
assert estimator
assert camera._path


def test_photon_pose_estimator_update():
estimator = photonvision.PhotonPoseEstimator(
robotpy_apriltag.loadAprilTagLayoutField(
robotpy_apriltag.AprilTagField.k2023ChargedUp
),
photonvision.PoseStrategy.AVERAGE_BEST_TARGETS,
photonvision.PhotonCamera("test_update"),
Transform3d(),
)
assert estimator.update() is None


def test_photon_pose_estimator_get_cam():
camera = photonvision.PhotonCamera("test_get_cam")
estimator = photonvision.PhotonPoseEstimator(
robotpy_apriltag.loadAprilTagLayoutField(
robotpy_apriltag.AprilTagField.k2023ChargedUp
),
photonvision.PoseStrategy.AVERAGE_BEST_TARGETS,
camera,
Transform3d(),
)
inner_cam = estimator.getCamera()
assert inner_cam is camera