[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

@@ -22,16 +22,16 @@
* SOFTWARE.
*/
#include "photonlib/PhotonCamera.h"
#include "photon/PhotonCamera.h"
#include <frc/Errors.h>
#include <frc/Timer.h>
#include <opencv2/core/mat.hpp>
#include "PhotonVersion.h"
#include "photonlib/Packet.h"
#include "photon/dataflow/structures/Packet.h"
namespace photonlib {
namespace photon {
constexpr const units::second_t VERSION_CHECK_INTERVAL = 5_s;
static const std::vector<std::string_view> PHOTON_PREFIX = {"/photonvision/"};
@@ -91,7 +91,7 @@ PhotonPipelineResult PhotonCamera::GetLatestResult() {
const auto value = rawBytesEntry.Get();
if (!value.size()) return result;
photonlib::Packet packet{value};
photon::Packet packet{value};
packet >> result;
@@ -192,4 +192,4 @@ void PhotonCamera::VerifyVersion() {
}
}
} // namespace photonlib
} // namespace photon

View File

@@ -22,7 +22,7 @@
* SOFTWARE.
*/
#include "photonlib/PhotonPoseEstimator.h"
#include "photon/PhotonPoseEstimator.h"
#include <cmath>
#include <iostream>
@@ -44,11 +44,11 @@
#include <units/math.h>
#include <units/time.h>
#include "photonlib/PhotonCamera.h"
#include "photonlib/PhotonPipelineResult.h"
#include "photonlib/PhotonTrackedTarget.h"
#include "photon/PhotonCamera.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
namespace photonlib {
namespace photon {
namespace detail {
cv::Point3d ToPoint3d(const frc::Translation3d& translation);
@@ -360,14 +360,14 @@ frc::Pose3d detail::ToPose3d(const cv::Mat& tvec, const cv::Mat& rvec) {
std::optional<EstimatedRobotPose> PhotonPoseEstimator::MultiTagOnCoprocStrategy(
PhotonPipelineResult result, std::optional<cv::Mat> camMat,
std::optional<cv::Mat> distCoeffs) {
if (result.MultiTagResult().result.isValid) {
if (result.MultiTagResult().result.isPresent) {
const auto field2camera = result.MultiTagResult().result.best;
const auto fieldToRobot =
frc::Pose3d() + field2camera + m_robotToCamera.Inverse();
return photonlib::EstimatedRobotPose(fieldToRobot, result.GetTimestamp(),
result.GetTargets(),
MULTI_TAG_PNP_ON_COPROCESSOR);
return photon::EstimatedRobotPose(fieldToRobot, result.GetTimestamp(),
result.GetTargets(),
MULTI_TAG_PNP_ON_COPROCESSOR);
}
return Update(result, std::nullopt, std::nullopt,
@@ -425,9 +425,9 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::MultiTagOnRioStrategy(
const Pose3d pose = detail::ToPose3d(tvec, rvec);
return photonlib::EstimatedRobotPose(
pose.TransformBy(m_robotToCamera.Inverse()), result.GetTimestamp(),
result.GetTargets(), MULTI_TAG_PNP_ON_RIO);
return photon::EstimatedRobotPose(pose.TransformBy(m_robotToCamera.Inverse()),
result.GetTimestamp(), result.GetTargets(),
MULTI_TAG_PNP_ON_RIO);
}
std::optional<EstimatedRobotPose>
@@ -476,4 +476,4 @@ PhotonPoseEstimator::AverageBestTargetsStrategy(PhotonPipelineResult result) {
result.GetTimestamp(), result.GetTargets(),
AVERAGE_BEST_TARGETS};
}
} // namespace photonlib
} // namespace photon

View File

@@ -1,113 +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.
*/
#include "photonlib/MultiTargetPNPResult.h"
namespace photonlib {
Packet& operator<<(Packet& packet, const MultiTargetPnpResult& target) {
packet << target.result;
size_t i;
for (i = 0; i < target.fiducialIdsUsed.capacity(); i++) {
if (i < target.fiducialIdsUsed.size()) {
packet << static_cast<int16_t>(target.fiducialIdsUsed[i]);
} else {
packet << static_cast<int16_t>(-1);
}
}
return packet;
}
Packet& operator>>(Packet& packet, MultiTargetPnpResult& target) {
packet >> target.result;
target.fiducialIdsUsed.clear();
for (size_t i = 0; i < target.fiducialIdsUsed.capacity(); i++) {
int16_t id = 0;
packet >> id;
if (id > -1) {
target.fiducialIdsUsed.push_back(id);
}
}
return packet;
}
// Encode a transform3d
Packet& operator<<(Packet& packet, const frc::Transform3d& transform) {
packet << transform.Translation().X().value()
<< transform.Translation().Y().value()
<< transform.Translation().Z().value()
<< transform.Rotation().GetQuaternion().W()
<< transform.Rotation().GetQuaternion().X()
<< transform.Rotation().GetQuaternion().Y()
<< transform.Rotation().GetQuaternion().Z();
return packet;
}
// Decode a transform3d
Packet& operator>>(Packet& packet, frc::Transform3d& transform) {
frc::Transform3d ret;
// We use these for best and alt transforms below
double x = 0;
double y = 0;
double z = 0;
double w = 0;
// decode and unitify translation
packet >> x >> y >> z;
const auto translation = frc::Translation3d(
units::meter_t(x), units::meter_t(y), units::meter_t(z));
// decode and add units to rotation
packet >> w >> x >> y >> z;
const auto rotation = frc::Rotation3d(frc::Quaternion(w, x, y, z));
transform = frc::Transform3d(translation, rotation);
return packet;
}
Packet& operator<<(Packet& packet, PNPResults const& result) {
packet << result.isValid << result.best << result.alt
<< result.bestReprojectionErr << result.altReprojectionErr
<< result.ambiguity;
return packet;
}
Packet& operator>>(Packet& packet, PNPResults& result) {
packet >> result.isValid >> result.best >> result.alt >>
result.bestReprojectionErr >> result.altReprojectionErr >>
result.ambiguity;
return packet;
}
} // namespace photonlib

View File

@@ -1,71 +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.
*/
#include "photonlib/PhotonPipelineResult.h"
namespace photonlib {
PhotonPipelineResult::PhotonPipelineResult(
units::second_t latency, std::span<const PhotonTrackedTarget> targets)
: latency(latency),
targets(targets.data(), targets.data() + targets.size()) {}
bool PhotonPipelineResult::operator==(const PhotonPipelineResult& other) const {
return latency == other.latency && targets == other.targets;
}
bool PhotonPipelineResult::operator!=(const PhotonPipelineResult& other) const {
return !operator==(other);
}
Packet& operator<<(Packet& packet, const PhotonPipelineResult& result) {
// Encode latency and number of targets.
packet << result.latency.value() * 1000 << result.m_pnpResults
<< static_cast<int8_t>(result.targets.size());
// Encode the information of each target.
for (auto& target : result.targets) packet << target;
// Return the packet
return packet;
}
Packet& operator>>(Packet& packet, PhotonPipelineResult& result) {
// Decode latency, existence of targets, and number of targets.
double latencyMillis = 0;
int8_t targetCount = 0;
packet >> latencyMillis >> result.m_pnpResults >> targetCount;
result.latency = units::second_t(latencyMillis / 1000.0);
result.targets.clear();
// Decode the information of each target.
for (int i = 0; i < targetCount; ++i) {
PhotonTrackedTarget target;
packet >> target;
result.targets.push_back(target);
}
return packet;
}
} // namespace photonlib

View File

@@ -1,147 +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.
*/
#include "photonlib/PhotonTrackedTarget.h"
#include <iostream>
#include <utility>
#include <frc/geometry/Translation2d.h>
#include <wpi/SmallVector.h>
static constexpr const uint8_t MAX_CORNERS = 8;
namespace photonlib {
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<std::pair<double, double>, 4> minAreaRectCorners,
const std::vector<std::pair<double, double>> detectedCorners)
: yaw(yaw),
pitch(pitch),
area(area),
skew(skew),
fiducialId(id),
bestCameraToTarget(pose),
altCameraToTarget(alternatePose),
poseAmbiguity(ambiguity),
minAreaRectCorners(minAreaRectCorners),
detectedCorners(detectedCorners) {}
bool PhotonTrackedTarget::operator==(const PhotonTrackedTarget& other) const {
return other.yaw == yaw && other.pitch == pitch && other.area == area &&
other.skew == skew && other.bestCameraToTarget == bestCameraToTarget &&
other.minAreaRectCorners == minAreaRectCorners;
}
bool PhotonTrackedTarget::operator!=(const PhotonTrackedTarget& other) const {
return !operator==(other);
}
Packet& operator<<(Packet& packet, const PhotonTrackedTarget& target) {
packet << target.yaw << target.pitch << target.area << target.skew
<< target.fiducialId
<< target.bestCameraToTarget.Translation().X().value()
<< target.bestCameraToTarget.Translation().Y().value()
<< target.bestCameraToTarget.Translation().Z().value()
<< target.bestCameraToTarget.Rotation().GetQuaternion().W()
<< target.bestCameraToTarget.Rotation().GetQuaternion().X()
<< target.bestCameraToTarget.Rotation().GetQuaternion().Y()
<< target.bestCameraToTarget.Rotation().GetQuaternion().Z()
<< target.altCameraToTarget.Translation().X().value()
<< target.altCameraToTarget.Translation().Y().value()
<< target.altCameraToTarget.Translation().Z().value()
<< target.altCameraToTarget.Rotation().GetQuaternion().W()
<< target.altCameraToTarget.Rotation().GetQuaternion().X()
<< target.altCameraToTarget.Rotation().GetQuaternion().Y()
<< target.altCameraToTarget.Rotation().GetQuaternion().Z()
<< target.poseAmbiguity;
for (int i = 0; i < 4; i++) {
packet << target.minAreaRectCorners[i].first
<< target.minAreaRectCorners[i].second;
}
uint8_t num_corners =
std::min<uint8_t>(target.detectedCorners.size(), MAX_CORNERS);
packet << num_corners;
for (size_t i = 0; i < target.detectedCorners.size(); i++) {
packet << target.detectedCorners[i].first
<< target.detectedCorners[i].second;
}
return packet;
}
Packet& operator>>(Packet& packet, PhotonTrackedTarget& target) {
packet >> target.yaw >> target.pitch >> target.area >> target.skew >>
target.fiducialId;
// We use these for best and alt transforms below
double x = 0;
double y = 0;
double z = 0;
double w = 0;
// First transform is the "best" pose
packet >> x >> y >> z;
const auto bestTranslation = frc::Translation3d(
units::meter_t(x), units::meter_t(y), units::meter_t(z));
packet >> w >> x >> y >> z;
const auto bestRotation = frc::Rotation3d(frc::Quaternion(w, x, y, z));
target.bestCameraToTarget = frc::Transform3d(bestTranslation, bestRotation);
// Second transform is the "alternate" pose
packet >> x >> y >> z;
const auto altTranslation = frc::Translation3d(
units::meter_t(x), units::meter_t(y), units::meter_t(z));
packet >> w >> x >> y >> z;
const auto altRotation = frc::Rotation3d(frc::Quaternion(w, x, y, z));
target.altCameraToTarget = frc::Transform3d(altTranslation, altRotation);
packet >> target.poseAmbiguity;
target.minAreaRectCorners.clear();
double first = 0;
double second = 0;
for (int i = 0; i < 4; i++) {
packet >> first >> second;
target.minAreaRectCorners.emplace_back(first, second);
}
uint8_t numCorners = 0;
packet >> numCorners;
target.detectedCorners.clear();
target.detectedCorners.reserve(numCorners);
for (size_t i = 0; i < numCorners; i++) {
packet >> first >> second;
target.detectedCorners.emplace_back(first, second);
}
return packet;
}
} // namespace photonlib