[photon-targeting] Move C++ targeting classes to photon-targetting (#1009)

* add classes to targeting and update gradle

* rename me

* Finish cleanup

* Formatting fixes

* just use common.gradle

* Update build.gradle

* Update config.gradle

* remove typo

* simplify

* Add Packet Headers

* move simulation classes into simulation folder

* draw in dependency

* fix

* Everything working minus tests cause im lazy

* formatting fixes

REMEMBER TO REMOVE UNUSED IMPORTS, IM JUST TOO LAZY TO CHECK RN

* move packet test to targeting

* Formatting fixes

* remove TargetCorner from c++

im not 100% sure but just doing std::pair<double, double> is sufficient and shouldnt conflict with protobuf

* think i added packet

* fix namespace issue

* organize imports in photon-targeting

* Formatting fixes

* remove ctors

* fix typo

* Add PNP and Multitag packet tests

* revert TargetCorner class

* Add Test placeholders

* remove annoying print

* Reorganize build and publish process

channeling inner Thad

* add targeting as flag

* Update config.gradle

* fix issue with platform binaries not building

* Update photonlib.json.in

casing still needs to be checked

* add minimum level back

* add back UTF-8 encoding of javadoc

* simplify publish model for photon-lib

* fix windows symbol generation

* formatting fixes

* move task from main gradle to config

* Update config.gradle
This commit is contained in:
Sriman Achanta
2023-11-19 15:16:22 -05:00
committed by GitHub
parent 308fd801d4
commit 994ea1e76b
50 changed files with 1132 additions and 910 deletions

View File

@@ -39,13 +39,17 @@
#include <units/time.h>
#include <wpi/deprecated.h>
#include "photonlib/PhotonPipelineResult.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"
namespace cv {
class Mat;
} // namespace cv
namespace photonlib {
namespace photon {
enum LEDMode : int { kDefault = -1, kOff = 0, kOn = 1, kBlink = 2 };
@@ -207,4 +211,4 @@ class PhotonCamera {
void VerifyVersion();
};
} // namespace photonlib
} // namespace photon

View File

@@ -30,14 +30,18 @@
#include <frc/geometry/Pose3d.h>
#include <frc/geometry/Transform3d.h>
#include "photonlib/PhotonCamera.h"
#include "photonlib/PhotonPipelineResult.h"
#include "photon/PhotonCamera.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"
namespace cv {
class Mat;
} // namespace cv
namespace photonlib {
namespace photon {
enum PoseStrategy {
LOWEST_AMBIGUITY = 0,
CLOSEST_TO_CAMERA_HEIGHT,
@@ -296,4 +300,4 @@ class PhotonPoseEstimator {
PhotonPipelineResult result);
};
} // namespace photonlib
} // namespace photon

View File

@@ -26,9 +26,13 @@
#include <cmath>
#include "photonlib/PhotonTrackedTarget.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"
namespace photonlib {
namespace photon {
namespace PhotonTargetSortMode {
@@ -82,4 +86,4 @@ struct CenterMost {
}
};
} // namespace PhotonTargetSortMode
} // namespace photonlib
} // namespace photon

View File

@@ -32,7 +32,13 @@
#include <units/length.h>
#include <units/math.h>
namespace photonlib {
#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"
namespace photon {
class PhotonUtils {
public:
/**
@@ -177,4 +183,4 @@ class PhotonUtils {
return fieldToTarget.TransformBy(targetToCamera);
}
};
} // namespace photonlib
} // namespace photon

View File

@@ -32,10 +32,15 @@
#include <networktables/NetworkTableInstance.h>
#include "photonlib/PhotonCamera.h"
#include "photonlib/PhotonTargetSortMode.h"
#include "photon/PhotonCamera.h"
#include "photon/PhotonTargetSortMode.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"
namespace photonlib {
namespace photon {
class SimPhotonCamera : public PhotonCamera {
public:
SimPhotonCamera(nt::NetworkTableInstance instance,
@@ -129,4 +134,4 @@ class SimPhotonCamera : public PhotonCamera {
nt::NetworkTableEntry versionEntry;
nt::RawPublisher rawBytesPublisher;
};
} // namespace photonlib
} // namespace photon

View File

@@ -34,8 +34,13 @@
#include "SimPhotonCamera.h"
#include "SimVisionTarget.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"
namespace photonlib {
namespace photon {
class SimVisionSystem {
public:
SimPhotonCamera cam;
@@ -218,4 +223,4 @@ class SimVisionSystem {
return (inRange && inHorizAngle && inVertAngle && targetBigEnough);
}
};
} // namespace photonlib
} // namespace photon

View File

@@ -27,7 +27,13 @@
#include <frc/geometry/Pose3d.h>
#include <units/area.h>
namespace photonlib {
#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"
namespace photon {
class SimVisionTarget {
public:
SimVisionTarget() = default;
@@ -56,4 +62,4 @@ class SimVisionTarget {
units::square_meter_t targetArea;
int targetId;
};
} // namespace photonlib
} // namespace photon

View File

@@ -1,61 +0,0 @@
/*
* MIT License
*
* Copyright (c) PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#pragma once
#include <frc/geometry/Transform3d.h>
#include <wpi/SmallVector.h>
#include "photonlib/Packet.h"
namespace photonlib {
class PNPResults {
public:
// This could be wrapped in an std::optional, but chose to do it this way to
// mirror Java
bool isValid;
frc::Transform3d best;
double bestReprojectionErr;
frc::Transform3d alt;
double altReprojectionErr;
double ambiguity;
friend Packet& operator<<(Packet& packet, const PNPResults& result);
friend Packet& operator>>(Packet& packet, PNPResults& result);
};
class MultiTargetPnpResult {
public:
PNPResults result;
wpi::SmallVector<int16_t, 32> fiducialIdsUsed;
friend Packet& operator<<(Packet& packet, const MultiTargetPnpResult& result);
friend Packet& operator>>(Packet& packet, MultiTargetPnpResult& result);
};
} // namespace photonlib

View File

@@ -1,130 +0,0 @@
/*
* MIT License
*
* Copyright (c) PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#pragma once
#include <algorithm>
#include <string>
#include <vector>
#include <wpi/Endian.h>
namespace photonlib {
/**
* A packet that holds byte-packed data to be sent over NetworkTables.
*/
class Packet {
public:
/**
* Constructs an empty packet.
*/
Packet() = default;
/**
* Constructs a packet with the given data.
* @param data The packet data.
*/
explicit Packet(std::vector<uint8_t> data) : packetData(data) {}
/**
* Clears the packet and resets the read and write positions.
*/
void Clear() {
packetData.clear();
readPos = 0;
writePos = 0;
}
/**
* Returns the packet data.
* @return The packet data.
*/
const std::vector<uint8_t>& GetData() { return packetData; }
/**
* Returns the number of bytes in the data.
* @return The number of bytes in the data.
*/
size_t GetDataSize() const { return packetData.size(); }
/**
* Adds a value to the data buffer. This should only be used with PODs.
* @tparam T The data type.
* @param src The data source.
* @return A reference to the current object.
*/
template <typename T>
Packet& operator<<(T src) {
packetData.resize(packetData.size() + sizeof(T));
std::memcpy(packetData.data() + writePos, &src, sizeof(T));
if constexpr (wpi::support::endian::system_endianness() ==
wpi::support::endianness::little) {
// Reverse to big endian for network conventions.
std::reverse(packetData.data() + writePos,
packetData.data() + writePos + sizeof(T));
}
writePos += sizeof(T);
return *this;
}
/**
* Extracts a value to the provided destination.
* @tparam T The type of value to extract.
* @param value The value to extract.
* @return A reference to the current object.
*/
template <typename T>
Packet& operator>>(T& value) {
if (!packetData.empty()) {
std::memcpy(&value, packetData.data() + readPos, sizeof(T));
if constexpr (wpi::support::endian::system_endianness() ==
wpi::support::endianness::little) {
// Reverse to little endian for host.
uint8_t& raw = reinterpret_cast<uint8_t&>(value);
std::reverse(&raw, &raw + sizeof(T));
}
}
readPos += sizeof(T);
return *this;
}
bool operator==(const Packet& right) const {
return packetData == right.packetData;
}
bool operator!=(const Packet& right) const { return !operator==(right); }
private:
// Data stored in the packet
std::vector<uint8_t> packetData;
size_t readPos = 0;
size_t writePos = 0;
};
} // namespace photonlib

View File

@@ -1,133 +0,0 @@
/*
* MIT License
*
* Copyright (c) PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#pragma once
#include <span>
#include <string>
#include <frc/Errors.h>
#include <units/time.h>
#include <wpi/SmallVector.h>
#include "photonlib/MultiTargetPNPResult.h"
#include "photonlib/Packet.h"
#include "photonlib/PhotonTrackedTarget.h"
namespace photonlib {
/**
* Represents a pipeline result from a PhotonCamera.
*/
class PhotonPipelineResult {
public:
/**
* Constructs an empty pipeline result.
*/
PhotonPipelineResult() = default;
/**
* Constructs a pipeline result.
* @param latency The latency in the pipeline.
* @param targets The list of targets identified by the pipeline.
*/
PhotonPipelineResult(units::second_t latency,
std::span<const PhotonTrackedTarget> targets);
/**
* Returns the best target in this pipeline result. If there are no targets,
* this method will return an empty target with all values set to zero. The
* best target is determined by the target sort mode in the PhotonVision UI.
*
* @return The best target of the pipeline result.
*/
PhotonTrackedTarget GetBestTarget() const {
if (!HasTargets() && !HAS_WARNED) {
FRC_ReportError(
frc::warn::Warning, "{}",
"This PhotonPipelineResult object has no targets associated with it! "
"Please check HasTargets() before calling this method. For more "
"information, please review the PhotonLib documentation at "
"http://docs.photonvision.org");
HAS_WARNED = true;
}
return HasTargets() ? targets[0] : PhotonTrackedTarget();
}
/**
* Returns the latency in the pipeline.
* @return The latency in the pipeline.
*/
units::second_t GetLatency() const { return latency; }
/**
* Returns the estimated time the frame was taken,
* This is much more accurate than using GetLatency()
* @return The timestamp in seconds or -1 if this result was not initiated
* with a timestamp.
*/
units::second_t GetTimestamp() const { return timestamp; }
/**
* Return the latest mulit-target result, as calculated on your coprocessor.
* Be sure to check getMultiTagResult().estimatedPose.isValid before using the
* pose estimate!
*/
const MultiTargetPnpResult& MultiTagResult() const { return m_pnpResults; }
/**
* Sets the timestamp in seconds
* @param timestamp The timestamp in seconds
*/
void SetTimestamp(const units::second_t timestamp) {
this->timestamp = timestamp;
}
/**
* Returns whether the pipeline has targets.
* @return Whether the pipeline has targets.
*/
bool HasTargets() const { return targets.size() > 0; }
/**
* Returns a reference to the vector of targets.
* @return A reference to the vector of targets.
*/
const std::span<const PhotonTrackedTarget> GetTargets() const {
return targets;
}
bool operator==(const PhotonPipelineResult& other) const;
bool operator!=(const PhotonPipelineResult& other) const;
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;
MultiTargetPnpResult m_pnpResults;
inline static bool HAS_WARNED = false;
};
} // namespace photonlib

View File

@@ -1,161 +0,0 @@
/*
* MIT License
*
* Copyright (c) PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#pragma once
#include <cstddef>
#include <string>
#include <utility>
#include <vector>
#include <frc/geometry/Transform3d.h>
#include <wpi/SmallVector.h>
#include "photonlib/Packet.h"
namespace photonlib {
/**
* Represents a tracked target within a pipeline.
*/
class PhotonTrackedTarget {
public:
/**
* Constructs an empty target.
*/
PhotonTrackedTarget() = default;
/**
* Constructs a target.
* @param yaw The yaw of the target.
* @param pitch The pitch of the target.
* @param area The area of the target.
* @param skew The skew of the target.
* @param pose The camera-relative pose of the target.
* @param alternatePose The alternate camera-relative pose of the target.
* @Param corners The corners of the bounding rectangle.
*/
PhotonTrackedTarget(
double yaw, double pitch, double area, double skew, int fiducialID,
const frc::Transform3d& pose, const frc::Transform3d& alternatePose,
double ambiguity,
const wpi::SmallVector<std::pair<double, double>, 4> corners,
const std::vector<std::pair<double, double>> detectedCorners);
/**
* Returns the target yaw (positive-left).
* @return The target yaw.
*/
double GetYaw() const { return yaw; }
/**
* Returns the target pitch (positive-up)
* @return The target pitch.
*/
double GetPitch() const { return pitch; }
/**
* Returns the target area (0-100).
* @return The target area.
*/
double GetArea() const { return area; }
/**
* Returns the target skew (counter-clockwise positive).
* @return The target skew.
*/
double GetSkew() const { return skew; }
/**
* Get the Fiducial ID of the target currently being tracked,
* or -1 if not set.
*/
int GetFiducialId() const { return fiducialId; }
/**
* Return a list of the 4 corners in image space (origin top left, x right, y
* down), in no particular order, of the minimum area bounding rectangle of
* this target
*/
wpi::SmallVector<std::pair<double, double>, 4> GetMinAreaRectCorners() const {
return minAreaRectCorners;
}
/**
* Return a list of the n corners in image space (origin top left, x right, y
* down), in no particular order, detected for this target.
* For fiducials, the order is known and is always counter-clock wise around
* the tag, like so
*
* -> +X 3 ----- 2
* | | |
* V + Y | |
* 0 ----- 1
*/
std::vector<std::pair<double, double>> GetDetectedCorners() {
return detectedCorners;
}
/**
* Get the ratio of pose reprojection errors, called ambiguity. Numbers above
* 0.2 are likely to be ambiguous. -1 if invalid.
*/
double GetPoseAmbiguity() const { return poseAmbiguity; }
/**
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to
* object/fiducial tag space (X forward, Y left, Z up) with the lowest
* reprojection error. The ratio between this and the alternate target's
* reprojection error is the ambiguity, which is between 0 and 1.
* @return The pose of the target relative to the robot.
*/
frc::Transform3d GetBestCameraToTarget() const { return bestCameraToTarget; }
/**
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to
* object/fiducial tag space (X forward, Y left, Z up) with the highest
* reprojection error
*/
frc::Transform3d GetAlternateCameraToTarget() const {
return altCameraToTarget;
}
bool operator==(const PhotonTrackedTarget& other) const;
bool operator!=(const PhotonTrackedTarget& other) const;
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;
double skew = 0;
int fiducialId;
frc::Transform3d bestCameraToTarget;
frc::Transform3d altCameraToTarget;
double poseAmbiguity;
wpi::SmallVector<std::pair<double, double>, 4> minAreaRectCorners;
std::vector<std::pair<double, double>> detectedCorners;
};
} // namespace photonlib