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

PhotonPoseEstimator: Move an lvalue reference #13

Closed
wants to merge 2 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
7 changes: 7 additions & 0 deletions gen/PhotonPoseEstimator.yml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,12 @@ classes:
PhotonPoseEstimator:
methods:
PhotonPoseEstimator:
cpp_code: |
[](frc::AprilTagFieldLayout aprilTags, photonlib::PoseStrategy strategy,
PhotonCamera& camera, frc::Transform3d robotToCamera) {
return std::make_unique<PhotonPoseEstimator>(
aprilTags, strategy, std::move(camera), robotToCamera);
}
GetFieldLayout:
GetPoseStrategy:
SetPoseStrategy:
Expand All @@ -25,3 +31,4 @@ classes:
SetLastPose:
Update:
GetCamera:
return_value_policy: reference_internal
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
2 changes: 1 addition & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,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
46 changes: 46 additions & 0 deletions tests/test_pose_estimator.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
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 not 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 not None
assert inner_cam is not camera