Skip to content

Commit

Permalink
Switch to {}
Browse files Browse the repository at this point in the history
  • Loading branch information
Matt M authored and Matt M committed Aug 19, 2024
1 parent 0e2ab7d commit fa58c1c
Show file tree
Hide file tree
Showing 9 changed files with 35 additions and 35 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,7 @@ PhotonPipelineResult PhotonCameraSim::Process(
heartbeatCounter++;
return PhotonPipelineResult{
PhotonPipelineMetadata{heartbeatCounter, 0,
units::microsecond_t{latency}.to<double>()},
units::microsecond_t{latency}.to<int64_t>()},
detectableTgts, multiTagResults};
}
void PhotonCameraSim::SubmitProcessedFrame(const PhotonPipelineResult& result) {
Expand Down
50 changes: 25 additions & 25 deletions photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,32 +52,32 @@ static std::vector<frc::AprilTag> tags = {
static frc::AprilTagFieldLayout aprilTags{tags, 54_ft, 27_ft};

static std::vector<photon::TargetCorner> 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<photon::TargetCorner> 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<photon::PhotonTrackedTarget> 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),
Expand Down Expand Up @@ -124,21 +124,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToCameraHeightStrategy) {

std::vector<photon::PhotonTrackedTarget> 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),
Expand Down Expand Up @@ -173,21 +173,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToReferencePoseStrategy) {

std::vector<photon::PhotonTrackedTarget> 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),
Expand Down Expand Up @@ -224,21 +224,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToLastPose) {

std::vector<photon::PhotonTrackedTarget> 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),
Expand All @@ -265,21 +265,21 @@ TEST(PhotonPoseEstimatorTest, ClosestToLastPose) {

std::vector<photon::PhotonTrackedTarget> 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),
Expand Down Expand Up @@ -310,21 +310,21 @@ TEST(PhotonPoseEstimatorTest, AverageBestPoses) {

std::vector<photon::PhotonTrackedTarget> 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),
Expand Down Expand Up @@ -359,21 +359,21 @@ TEST(PhotonPoseEstimatorTest, PoseCache) {

std::vector<photon::PhotonTrackedTarget> 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),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class MultiTargetPNPResult : public MultiTargetPNPResult_PhotonStruct {

template <typename... Args>
explicit MultiTargetPNPResult(Args&&... args)
: Base(std::forward<Args>(args)...) {}
: Base{std::forward<Args>(args)...} {}

friend bool operator==(MultiTargetPNPResult const&,
MultiTargetPNPResult const&) = default;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class PhotonPipelineMetadata : public PhotonPipelineMetadata_PhotonStruct {

template <typename... Args>
explicit PhotonPipelineMetadata(Args&&... args)
: Base(std::forward<Args>(args)...) {}
: Base{std::forward<Args>(args)...} {}

friend bool operator==(PhotonPipelineMetadata const&,
PhotonPipelineMetadata const&) = default;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -61,7 +62,7 @@ class PhotonPipelineResult : public PhotonPipelineResult_PhotonStruct {

template <typename... Args>
explicit PhotonPipelineResult(Args&&... args)
: Base(std::forward<Args>(args)...) {}
: Base{std::forward<Args>(args)...} {}

/**
* Returns the best target in this pipeline result. If there are no targets,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class PhotonTrackedTarget : public PhotonTrackedTarget_PhotonStruct {

template <typename... Args>
explicit PhotonTrackedTarget(Args&&... args)
: Base(std::forward<Args>(args)...) {}
: Base{std::forward<Args>(args)...} {}

/**
* Returns the target yaw (positive-left).
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ struct PnpResult : public PnpResult_PhotonStruct {
explicit PnpResult(Base&& data) : Base(data) {}

template <typename... Args>
explicit PnpResult(Args&&... args) : Base(std::forward<Args>(args)...) {}
explicit PnpResult(Args&&... args) : Base{std::forward<Args>(args)...} {}

friend bool operator==(PnpResult const&, PnpResult const&) = default;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class TargetCorner : public TargetCorner_PhotonStruct {
explicit TargetCorner(Base&& data) : Base(data) {}

template <typename... Args>
explicit TargetCorner(Args&&... args) : Base(std::forward<Args>(args)...) {}
explicit TargetCorner(Args&&... args) : Base{std::forward<Args>(args)...} {}

friend bool operator==(TargetCorner const&, TargetCorner const&) = default;
};
Expand Down
5 changes: 2 additions & 3 deletions photon-targeting/src/test/native/cpp/PacketTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,9 +84,8 @@ TEST(PacketTest, PnpResult) {
// }

TEST(PacketTest, PhotonPipelineResult) {
PhotonPipelineResult result(
PhotonPipelineMetadata(0, 0, 1),
std::vector<PhotonTrackedTarget>{}, std::nullopt);
PhotonPipelineResult result(PhotonPipelineMetadata(0, 0, 1),
std::vector<PhotonTrackedTarget>{}, std::nullopt);

Packet p;
p.Pack<decltype(result)>(result);
Expand Down

0 comments on commit fa58c1c

Please sign in to comment.