Skip to content

Commit

Permalink
remove TargetCorner from c++
Browse files Browse the repository at this point in the history
im not 100% sure but just doing std::pair<double, double> is sufficient and shouldnt conflict with protobuf
  • Loading branch information
srimanachanta committed Nov 18, 2023
1 parent b7b0477 commit 6d5332c
Show file tree
Hide file tree
Showing 14 changed files with 15 additions and 90 deletions.
1 change: 0 additions & 1 deletion photon-lib/src/main/native/include/photon/PhotonCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

namespace cv {
class Mat;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

namespace cv {
class Mat;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

namespace photon {

Expand Down
1 change: 0 additions & 1 deletion photon-lib/src/main/native/include/photon/PhotonUtils.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

namespace photon {
class PhotonUtils {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

namespace photon {
class SimPhotonCamera : public PhotonCamera {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

namespace photon {
class SimVisionSystem {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

namespace photon {
class SimVisionTarget {
Expand Down
1 change: 0 additions & 1 deletion photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

static std::vector<frc::AprilTag> tags = {
{0, frc::Pose3d(units::meter_t(3), units::meter_t(3), units::meter_t(3),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,6 @@
#include <frc/geometry/Translation2d.h>
#include <wpi/SmallVector.h>

#include "photon/targeting/TargetCorner.h"

static constexpr const uint8_t MAX_CORNERS = 8;

using namespace photon;
Expand All @@ -33,8 +31,8 @@ PhotonTrackedTarget::PhotonTrackedTarget(
double yaw, double pitch, double area, double skew, int id,
const frc::Transform3d& pose, const frc::Transform3d& alternatePose,
double ambiguity,
const wpi::SmallVector<TargetCorner, 4> minAreaRectCorners,
const std::vector<TargetCorner> detectedCorners)
const wpi::SmallVector<std::pair<double, double>, 4> minAreaRectCorners,
const std::vector<std::pair<double, double>> detectedCorners)
: yaw(yaw),
pitch(pitch),
area(area),
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,6 @@ class PhotonPipelineResult {
friend Packet& operator<<(Packet& packet, const PhotonPipelineResult& result);
friend Packet& operator>>(Packet& packet, PhotonPipelineResult& result);

private:
units::second_t latency = 0_s;
units::second_t timestamp = -1_s;
wpi::SmallVector<PhotonTrackedTarget, 10> targets;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#include <frc/geometry/Transform3d.h>
#include <wpi/SmallVector.h>

#include "TargetCorner.h"
#include "photon/dataflow/structures/Packet.h"

namespace photon {
Expand Down Expand Up @@ -54,8 +53,8 @@ class PhotonTrackedTarget {
double yaw, double pitch, double area, double skew, int fiducialID,
const frc::Transform3d& pose, const frc::Transform3d& alternatePose,
double ambiguity,
const wpi::SmallVector<TargetCorner, 4> minAreaRectCorners,
const std::vector<TargetCorner> detectedCorners);
const wpi::SmallVector<std::pair<double, double>, 4> minAreaRectCorners,
const std::vector<std::pair<double, double>> detectedCorners);

/**
* Returns the target yaw (positive-left).
Expand Down Expand Up @@ -92,7 +91,8 @@ class PhotonTrackedTarget {
* down), in no particular order, of the minimum area bounding rectangle of
* this target
*/
const wpi::SmallVector<TargetCorner, 4>& GetMinAreaRectCorners() const {
const wpi::SmallVector<std::pair<double, double>, 4>& GetMinAreaRectCorners()
const {
return minAreaRectCorners;
}

Expand All @@ -107,7 +107,7 @@ class PhotonTrackedTarget {
* V + Y | |
* 0 ----- 1
*/
const std::vector<TargetCorner>& GetDetectedCorners() const {
const std::vector<std::pair<double, double>>& GetDetectedCorners() const {
return detectedCorners;
}

Expand Down Expand Up @@ -140,7 +140,6 @@ class PhotonTrackedTarget {
friend Packet& operator<<(Packet& packet, const PhotonTrackedTarget& target);
friend Packet& operator>>(Packet& packet, PhotonTrackedTarget& target);

private:
double yaw = 0;
double pitch = 0;
double area = 0;
Expand All @@ -149,7 +148,7 @@ class PhotonTrackedTarget {
frc::Transform3d bestCameraToTarget;
frc::Transform3d altCameraToTarget;
double poseAmbiguity;
wpi::SmallVector<TargetCorner, 4> minAreaRectCorners;
std::vector<TargetCorner> detectedCorners;
wpi::SmallVector<std::pair<double, double>, 4> minAreaRectCorners;
std::vector<std::pair<double, double>> detectedCorners;
};
} // namespace photon

This file was deleted.

15 changes: 6 additions & 9 deletions photon-targeting/src/test/native/cpp/PacketTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@
#include <units/angle.h>

#include "gtest/gtest.h"

#include "photon/dataflow/structures/Packet.h"
#include "photon/targeting/MultiTargetPNPResult.h"
#include "photon/targeting/PNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/TargetCorner.h"

TEST(PacketTest, PhotonTrackedTarget) {
photon::PhotonTrackedTarget target{
Expand Down Expand Up @@ -77,10 +77,8 @@ TEST(PacketTest, PhotonPipelineResult) {
frc::Transform3d(frc::Translation3d(1_m, 2_m, 3_m),
frc::Rotation3d(1_rad, 2_rad, 3_rad)),
-1,
{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)}},
{std::pair{1, 2}, std::pair{3, 4}, std::pair{5, 6}, std::pair{7, 8}},
{std::pair{1, 2}, std::pair{3, 4}, std::pair{5, 6}, std::pair{7, 8}}},
photon::PhotonTrackedTarget{
3.0,
-4.0,
Expand All @@ -92,10 +90,9 @@ TEST(PacketTest, PhotonPipelineResult) {
frc::Transform3d(frc::Translation3d(1_m, 2_m, 3_m),
frc::Rotation3d(1_rad, 2_rad, 3_rad)),
-1,
{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)}}};
{std::pair{1, 2}, std::pair{3, 4}, std::pair{5, 6}, std::pair{7, 8}},
{std::pair{1, 2}, std::pair{3, 4}, std::pair{5, 6},
std::pair{7, 8}}}};

photon::PhotonPipelineResult result2{2_s, targets};
photon::Packet p2;
Expand Down

0 comments on commit 6d5332c

Please sign in to comment.