diff --git a/photon-lib/src/main/native/cpp/photon/simulation/PhotonCameraSim.cpp b/photon-lib/src/main/native/cpp/photon/simulation/PhotonCameraSim.cpp index 089ad80a88..94c31f0f47 100644 --- a/photon-lib/src/main/native/cpp/photon/simulation/PhotonCameraSim.cpp +++ b/photon-lib/src/main/native/cpp/photon/simulation/PhotonCameraSim.cpp @@ -330,7 +330,7 @@ PhotonPipelineResult PhotonCameraSim::Process( heartbeatCounter++; return PhotonPipelineResult{ PhotonPipelineMetadata{heartbeatCounter, 0, - units::microsecond_t{latency}.to()}, + units::microsecond_t{latency}.to()}, detectableTgts, multiTagResults}; } void PhotonCameraSim::SubmitProcessedFrame(const PhotonPipelineResult& result) { diff --git a/photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp b/photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp index 99ba5e3bcc..3d8c86d9c8 100644 --- a/photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp +++ b/photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp @@ -52,32 +52,32 @@ static std::vector tags = { static frc::AprilTagFieldLayout aprilTags{tags, 54_ft, 27_ft}; static std::vector corners{ - photon::TargetCorner{1, 2}, photon::TargetCorner{3, 4}, - photon::TargetCorner{5, 6}, photon::TargetCorner{7, 8}}; + photon::TargetCorner{1., 2.}, photon::TargetCorner{3., 4.}, + photon::TargetCorner{5., 6.}, photon::TargetCorner{7., 8.}}; static std::vector detectedCorners{ - photon::TargetCorner{1, 2}, photon::TargetCorner{3, 4}, - photon::TargetCorner{5, 6}, photon::TargetCorner{7, 8}}; + photon::TargetCorner{1., 2.}, photon::TargetCorner{3., 4.}, + photon::TargetCorner{5., 6.}, photon::TargetCorner{7., 8.}}; TEST(PhotonPoseEstimatorTest, LowestAmbiguityStrategy) { photon::PhotonCamera cameraOne = photon::PhotonCamera("test"); std::vector targets{ photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.0, 4.0, 0, -1, -1, + 3.0, -4.0, 9.0, 4.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(1_m, 2_m, 3_m), frc::Rotation3d(1_rad, 2_rad, 3_rad)), frc::Transform3d(frc::Translation3d(1_m, 2_m, 3_m), frc::Rotation3d(1_rad, 2_rad, 3_rad)), 0.7, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.1, 6.7, 1, -1, -1, + 3.0, -4.0, 9.1, 6.7, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(4_m, 2_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(4_m, 2_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.3, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 9.0, -2.0, 19.0, 3.0, 0, -1, -1, + 9.0, -2.0, 19.0, 3.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(1_m, 2_m, 3_m), frc::Rotation3d(1_rad, 2_rad, 3_rad)), frc::Transform3d(frc::Translation3d(1_m, 2_m, 3_m), @@ -124,21 +124,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToCameraHeightStrategy) { std::vector targets{ photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.0, 4.0, 1, -1, -1, + 3.0, -4.0, 9.0, 4.0, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(0_m, 0_m, 0_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(1_m, 1_m, 1_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.7, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.1, 6.7, 1, -1, -1, + 3.0, -4.0, 9.1, 6.7, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(2_m, 2_m, 2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.3, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 9.0, -2.0, 19.0, 3.0, 0, -1, -1, + 9.0, -2.0, 19.0, 3.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(4_m, 4_m, 4_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(5_m, 5_m, 5_m), @@ -173,21 +173,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToReferencePoseStrategy) { std::vector targets{ photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.0, 4.0, 1, -1, -1, + 3.0, -4.0, 9.0, 4.0, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(0_m, 0_m, 0_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(1_m, 1_m, 1_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.7, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.1, 6.7, 1, -1, -1, + 3.0, -4.0, 9.1, 6.7, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(2_m, 2_m, 2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.3, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 9.0, -2.0, 19.0, 3.0, 0, -1, -1, + 9.0, -2.0, 19.0, 3.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(2.2_m, 2.2_m, 2.2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(2_m, 1.9_m, 2.1_m), @@ -224,21 +224,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToLastPose) { std::vector targets{ photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.0, 4.0, 1, -1, -1, + 3.0, -4.0, 9.0, 4.0, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(0_m, 0_m, 0_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(1_m, 1_m, 1_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.7, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.1, 6.7, 1, -1, -1, + 3.0, -4.0, 9.1, 6.7, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(2_m, 2_m, 2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.3, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 9.0, -2.0, 19.0, 3.0, 0, -1, -1, + 9.0, -2.0, 19.0, 3.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(2.2_m, 2.2_m, 2.2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(2_m, 1.9_m, 2.1_m), @@ -265,21 +265,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToLastPose) { std::vector targetsThree{ photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.0, 4.0, 1, -1, -1, + 3.0, -4.0, 9.0, 4.0, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(0_m, 0_m, 0_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(1_m, 1_m, 1_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.7, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.1, 6.7, 0, -1, -1, + 3.0, -4.0, 9.1, 6.7, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(2.1_m, 1.9_m, 2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.3, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 9.0, -2.0, 19.0, 3.0, 0, -1, -1, + 9.0, -2.0, 19.0, 3.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(2.4_m, 2.4_m, 2.2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(2_m, 1_m, 2_m), @@ -310,21 +310,21 @@ TEST(PhotonPoseEstimatorTest, AverageBestPoses) { std::vector targets{ photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.0, 4.0, 0, -1, -1, + 3.0, -4.0, 9.0, 4.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(2_m, 2_m, 2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(1_m, 1_m, 1_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.7, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.1, 6.7, 1, -1, -1, + 3.0, -4.0, 9.1, 6.7, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.3, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 9.0, -2.0, 19.0, 3.0, 0, -1, -1, + 9.0, -2.0, 19.0, 3.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(0_m, 0_m, 0_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(2_m, 1.9_m, 2.1_m), @@ -359,21 +359,21 @@ TEST(PhotonPoseEstimatorTest, PoseCache) { std::vector targets{ photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.0, 4.0, 0, -1, -1, + 3.0, -4.0, 9.0, 4.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(2_m, 2_m, 2_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(1_m, 1_m, 1_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.7, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 3.0, -4.0, 9.1, 6.7, 1, -1, -1, + 3.0, -4.0, 9.1, 6.7, 1, -1, -1.f, frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(3_m, 3_m, 3_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), 0.3, corners, detectedCorners}, photon::PhotonTrackedTarget{ - 9.0, -2.0, 19.0, 3.0, 0, -1, -1, + 9.0, -2.0, 19.0, 3.0, 0, -1, -1.f, frc::Transform3d(frc::Translation3d(0_m, 0_m, 0_m), frc::Rotation3d(0_rad, 0_rad, 0_rad)), frc::Transform3d(frc::Translation3d(2_m, 1.9_m, 2.1_m), diff --git a/photon-targeting/src/main/native/include/photon/targeting/MultiTargetPNPResult.h b/photon-targeting/src/main/native/include/photon/targeting/MultiTargetPNPResult.h index 2624364c2b..3c8790e4f8 100644 --- a/photon-targeting/src/main/native/include/photon/targeting/MultiTargetPNPResult.h +++ b/photon-targeting/src/main/native/include/photon/targeting/MultiTargetPNPResult.h @@ -35,7 +35,7 @@ class MultiTargetPNPResult : public MultiTargetPNPResult_PhotonStruct { template explicit MultiTargetPNPResult(Args&&... args) - : Base(std::forward(args)...) {} + : Base{std::forward(args)...} {} friend bool operator==(MultiTargetPNPResult const&, MultiTargetPNPResult const&) = default; diff --git a/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineMetadata.h b/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineMetadata.h index f182e442ac..ba72256d9e 100644 --- a/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineMetadata.h +++ b/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineMetadata.h @@ -30,7 +30,7 @@ class PhotonPipelineMetadata : public PhotonPipelineMetadata_PhotonStruct { template explicit PhotonPipelineMetadata(Args&&... args) - : Base(std::forward(args)...) {} + : Base{std::forward(args)...} {} friend bool operator==(PhotonPipelineMetadata const&, PhotonPipelineMetadata const&) = default; diff --git a/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineResult.h b/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineResult.h index f6495d9051..82a67b6953 100644 --- a/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineResult.h +++ b/photon-targeting/src/main/native/include/photon/targeting/PhotonPipelineResult.h @@ -38,6 +38,7 @@ class PhotonPipelineResult : public PhotonPipelineResult_PhotonStruct { using Base = PhotonPipelineResult_PhotonStruct; public: + PhotonPipelineResult() : Base() {} explicit PhotonPipelineResult(Base&& data) : Base(data) {} // Don't forget to deal with our ntRecieveTimestamp @@ -61,7 +62,7 @@ class PhotonPipelineResult : public PhotonPipelineResult_PhotonStruct { template explicit PhotonPipelineResult(Args&&... args) - : Base(std::forward(args)...) {} + : Base{std::forward(args)...} {} /** * Returns the best target in this pipeline result. If there are no targets, diff --git a/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h b/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h index 41059308a9..66f6a0634e 100644 --- a/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h +++ b/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h @@ -41,7 +41,7 @@ class PhotonTrackedTarget : public PhotonTrackedTarget_PhotonStruct { template explicit PhotonTrackedTarget(Args&&... args) - : Base(std::forward(args)...) {} + : Base{std::forward(args)...} {} /** * Returns the target yaw (positive-left). diff --git a/photon-targeting/src/main/native/include/photon/targeting/PnpResult.h b/photon-targeting/src/main/native/include/photon/targeting/PnpResult.h index 82d9b2db70..f07b46c46b 100644 --- a/photon-targeting/src/main/native/include/photon/targeting/PnpResult.h +++ b/photon-targeting/src/main/native/include/photon/targeting/PnpResult.h @@ -32,7 +32,7 @@ struct PnpResult : public PnpResult_PhotonStruct { explicit PnpResult(Base&& data) : Base(data) {} template - explicit PnpResult(Args&&... args) : Base(std::forward(args)...) {} + explicit PnpResult(Args&&... args) : Base{std::forward(args)...} {} friend bool operator==(PnpResult const&, PnpResult const&) = default; }; diff --git a/photon-targeting/src/main/native/include/photon/targeting/TargetCorner.h b/photon-targeting/src/main/native/include/photon/targeting/TargetCorner.h index 1456b7eb3d..48d928a6b9 100644 --- a/photon-targeting/src/main/native/include/photon/targeting/TargetCorner.h +++ b/photon-targeting/src/main/native/include/photon/targeting/TargetCorner.h @@ -29,7 +29,7 @@ class TargetCorner : public TargetCorner_PhotonStruct { explicit TargetCorner(Base&& data) : Base(data) {} template - explicit TargetCorner(Args&&... args) : Base(std::forward(args)...) {} + explicit TargetCorner(Args&&... args) : Base{std::forward(args)...} {} friend bool operator==(TargetCorner const&, TargetCorner const&) = default; }; diff --git a/photon-targeting/src/test/native/cpp/PacketTest.cpp b/photon-targeting/src/test/native/cpp/PacketTest.cpp index 76891f5297..802bc7f969 100644 --- a/photon-targeting/src/test/native/cpp/PacketTest.cpp +++ b/photon-targeting/src/test/native/cpp/PacketTest.cpp @@ -84,9 +84,8 @@ TEST(PacketTest, PnpResult) { // } TEST(PacketTest, PhotonPipelineResult) { - PhotonPipelineResult result( - PhotonPipelineMetadata(0, 0, 1), - std::vector{}, std::nullopt); + PhotonPipelineResult result(PhotonPipelineMetadata(0, 0, 1), + std::vector{}, std::nullopt); Packet p; p.Pack(result);