mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
SCRIPT namespace replacements
This commit is contained in:
committed by
Peter Johnson
parent
ae6c043632
commit
9aca8e0fd6
@@ -5,7 +5,7 @@
|
||||
#include "wpi/apriltag/AprilTagDetector.hpp"
|
||||
|
||||
int main() {
|
||||
frc::AprilTagDetector detector;
|
||||
wpi::apriltag::AprilTagDetector detector;
|
||||
detector.AddFamily("tag16h5");
|
||||
detector.SetConfig({.refineEdges = false});
|
||||
}
|
||||
|
||||
@@ -20,9 +20,9 @@
|
||||
#include "tag16h5.h"
|
||||
#include "tag36h11.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
static bool FamilyToImage(wpi::RawFrame* frame, apriltag_family_t* family,
|
||||
static bool FamilyToImage(wpi::util::RawFrame* frame, apriltag_family_t* family,
|
||||
int id) {
|
||||
image_u8_t* image = apriltag_to_image(family, id);
|
||||
size_t totalDataSize = image->height * image->stride;
|
||||
@@ -37,25 +37,25 @@ static bool FamilyToImage(wpi::RawFrame* frame, apriltag_family_t* family,
|
||||
return rv;
|
||||
}
|
||||
|
||||
bool AprilTag::Generate36h11AprilTagImage(wpi::RawFrame* frame, int id) {
|
||||
bool AprilTag::Generate36h11AprilTagImage(wpi::util::RawFrame* frame, int id) {
|
||||
apriltag_family_t* tagFamily = tag36h11_create();
|
||||
bool rv = FamilyToImage(frame, tagFamily, id);
|
||||
tag36h11_destroy(tagFamily);
|
||||
return rv;
|
||||
}
|
||||
|
||||
bool AprilTag::Generate16h5AprilTagImage(wpi::RawFrame* frame, int id) {
|
||||
bool AprilTag::Generate16h5AprilTagImage(wpi::util::RawFrame* frame, int id) {
|
||||
apriltag_family_t* tagFamily = tag16h5_create();
|
||||
bool rv = FamilyToImage(frame, tagFamily, id);
|
||||
tag16h5_destroy(tagFamily);
|
||||
return rv;
|
||||
}
|
||||
|
||||
void frc::to_json(wpi::json& json, const AprilTag& apriltag) {
|
||||
json = wpi::json{{"ID", apriltag.ID}, {"pose", apriltag.pose}};
|
||||
void wpi::apriltag::to_json(wpi::util::json& json, const AprilTag& apriltag) {
|
||||
json = wpi::util::json{{"ID", apriltag.ID}, {"pose", apriltag.pose}};
|
||||
}
|
||||
|
||||
void frc::from_json(const wpi::json& json, AprilTag& apriltag) {
|
||||
void wpi::apriltag::from_json(const wpi::util::json& json, AprilTag& apriltag) {
|
||||
apriltag.ID = json.at("ID").get<int>();
|
||||
apriltag.pose = json.at("pose").get<Pose3d>();
|
||||
apriltag.pose = json.at("pose").get<wpi::math::Pose3d>();
|
||||
}
|
||||
|
||||
@@ -16,7 +16,7 @@
|
||||
|
||||
#include "apriltag.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
static_assert(sizeof(AprilTagDetection) == sizeof(apriltag_detection_t),
|
||||
"structure sizes don't match");
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
#include "tag16h5.h"
|
||||
#include "tag36h11.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
AprilTagDetector::Results::Results(void* impl, const private_init&)
|
||||
: span{reinterpret_cast<AprilTagDetection**>(
|
||||
|
||||
@@ -14,26 +14,26 @@
|
||||
#include "wpi/util/json.hpp"
|
||||
#include "wpi/util/raw_ostream.hpp"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
AprilTagFieldLayout::AprilTagFieldLayout(std::string_view path) {
|
||||
auto fileBuffer = wpi::MemoryBuffer::GetFile(path);
|
||||
auto fileBuffer = wpi::util::MemoryBuffer::GetFile(path);
|
||||
if (!fileBuffer) {
|
||||
throw std::runtime_error(fmt::format("Cannot open file: {}", path));
|
||||
}
|
||||
|
||||
wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer());
|
||||
wpi::util::json json = wpi::util::json::parse(fileBuffer.value()->GetCharBuffer());
|
||||
|
||||
for (const auto& tag : json.at("tags").get<std::vector<AprilTag>>()) {
|
||||
m_apriltags[tag.ID] = tag;
|
||||
}
|
||||
m_fieldWidth = units::meter_t{json.at("field").at("width").get<double>()};
|
||||
m_fieldLength = units::meter_t{json.at("field").at("length").get<double>()};
|
||||
m_fieldWidth = wpi::units::meter_t{json.at("field").at("width").get<double>()};
|
||||
m_fieldLength = wpi::units::meter_t{json.at("field").at("length").get<double>()};
|
||||
}
|
||||
|
||||
AprilTagFieldLayout::AprilTagFieldLayout(std::vector<AprilTag> apriltags,
|
||||
units::meter_t fieldLength,
|
||||
units::meter_t fieldWidth)
|
||||
wpi::units::meter_t fieldLength,
|
||||
wpi::units::meter_t fieldWidth)
|
||||
: m_fieldLength(std::move(fieldLength)),
|
||||
m_fieldWidth(std::move(fieldWidth)) {
|
||||
for (const auto& tag : apriltags) {
|
||||
@@ -41,11 +41,11 @@ AprilTagFieldLayout::AprilTagFieldLayout(std::vector<AprilTag> apriltags,
|
||||
}
|
||||
}
|
||||
|
||||
units::meter_t AprilTagFieldLayout::GetFieldLength() const {
|
||||
wpi::units::meter_t AprilTagFieldLayout::GetFieldLength() const {
|
||||
return m_fieldLength;
|
||||
}
|
||||
|
||||
units::meter_t AprilTagFieldLayout::GetFieldWidth() const {
|
||||
wpi::units::meter_t AprilTagFieldLayout::GetFieldWidth() const {
|
||||
return m_fieldWidth;
|
||||
}
|
||||
|
||||
@@ -61,26 +61,26 @@ std::vector<AprilTag> AprilTagFieldLayout::GetTags() const {
|
||||
void AprilTagFieldLayout::SetOrigin(OriginPosition origin) {
|
||||
switch (origin) {
|
||||
case OriginPosition::kBlueAllianceWallRightSide:
|
||||
SetOrigin(Pose3d{});
|
||||
SetOrigin(wpi::math::Pose3d{});
|
||||
break;
|
||||
case OriginPosition::kRedAllianceWallRightSide:
|
||||
SetOrigin(Pose3d{Translation3d{m_fieldLength, m_fieldWidth, 0_m},
|
||||
Rotation3d{0_deg, 0_deg, 180_deg}});
|
||||
SetOrigin(wpi::math::Pose3d{wpi::math::Translation3d{m_fieldLength, m_fieldWidth, 0_m},
|
||||
wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}});
|
||||
break;
|
||||
default:
|
||||
throw std::invalid_argument("Invalid origin");
|
||||
}
|
||||
}
|
||||
|
||||
void AprilTagFieldLayout::SetOrigin(const Pose3d& origin) {
|
||||
void AprilTagFieldLayout::SetOrigin(const wpi::math::Pose3d& origin) {
|
||||
m_origin = origin;
|
||||
}
|
||||
|
||||
Pose3d AprilTagFieldLayout::GetOrigin() const {
|
||||
wpi::math::Pose3d AprilTagFieldLayout::GetOrigin() const {
|
||||
return m_origin;
|
||||
}
|
||||
|
||||
std::optional<frc::Pose3d> AprilTagFieldLayout::GetTagPose(int ID) const {
|
||||
std::optional<wpi::math::Pose3d> AprilTagFieldLayout::GetTagPose(int ID) const {
|
||||
const auto& it = m_apriltags.find(ID);
|
||||
if (it == m_apriltags.end()) {
|
||||
return std::nullopt;
|
||||
@@ -91,43 +91,43 @@ std::optional<frc::Pose3d> AprilTagFieldLayout::GetTagPose(int ID) const {
|
||||
void AprilTagFieldLayout::Serialize(std::string_view path) {
|
||||
std::error_code error_code;
|
||||
|
||||
wpi::raw_fd_ostream output{path, error_code};
|
||||
wpi::util::raw_fd_ostream output{path, error_code};
|
||||
if (error_code) {
|
||||
throw std::runtime_error(fmt::format("Cannot open file: {}", path));
|
||||
}
|
||||
|
||||
wpi::json json = *this;
|
||||
wpi::util::json json = *this;
|
||||
output << json;
|
||||
output.flush();
|
||||
}
|
||||
|
||||
void frc::to_json(wpi::json& json, const AprilTagFieldLayout& layout) {
|
||||
void wpi::apriltag::to_json(wpi::util::json& json, const AprilTagFieldLayout& layout) {
|
||||
std::vector<AprilTag> tagVector;
|
||||
tagVector.reserve(layout.m_apriltags.size());
|
||||
for (const auto& pair : layout.m_apriltags) {
|
||||
tagVector.push_back(pair.second);
|
||||
}
|
||||
|
||||
json = wpi::json{{"field",
|
||||
json = wpi::util::json{{"field",
|
||||
{{"length", layout.m_fieldLength.value()},
|
||||
{"width", layout.m_fieldWidth.value()}}},
|
||||
{"tags", tagVector}};
|
||||
}
|
||||
|
||||
void frc::from_json(const wpi::json& json, AprilTagFieldLayout& layout) {
|
||||
void wpi::apriltag::from_json(const wpi::util::json& json, AprilTagFieldLayout& layout) {
|
||||
layout.m_apriltags.clear();
|
||||
for (const auto& tag : json.at("tags").get<std::vector<AprilTag>>()) {
|
||||
layout.m_apriltags[tag.ID] = tag;
|
||||
}
|
||||
|
||||
layout.m_fieldLength =
|
||||
units::meter_t{json.at("field").at("length").get<double>()};
|
||||
wpi::units::meter_t{json.at("field").at("length").get<double>()};
|
||||
layout.m_fieldWidth =
|
||||
units::meter_t{json.at("field").at("width").get<double>()};
|
||||
wpi::units::meter_t{json.at("field").at("width").get<double>()};
|
||||
}
|
||||
|
||||
// Use namespace declaration for forward declaration
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
// C++ generated from resource files
|
||||
std::string_view GetResource_2022_rapidreact_json();
|
||||
@@ -136,7 +136,7 @@ std::string_view GetResource_2024_crescendo_json();
|
||||
std::string_view GetResource_2025_reefscape_welded_json();
|
||||
std::string_view GetResource_2025_reefscape_andymark_json();
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) {
|
||||
std::string_view fieldString;
|
||||
@@ -160,10 +160,10 @@ AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) {
|
||||
throw std::invalid_argument("Invalid Field");
|
||||
}
|
||||
|
||||
wpi::json json = wpi::json::parse(fieldString);
|
||||
wpi::util::json json = wpi::util::json::parse(fieldString);
|
||||
return json.get<AprilTagFieldLayout>();
|
||||
}
|
||||
|
||||
AprilTagFieldLayout frc::LoadAprilTagLayoutField(AprilTagField field) {
|
||||
AprilTagFieldLayout wpi::apriltag::LoadAprilTagLayoutField(AprilTagField field) {
|
||||
return AprilTagFieldLayout::LoadField(field);
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
double AprilTagPoseEstimate::GetAmbiguity() const {
|
||||
auto min = (std::min)(error1, error2);
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
#include "apriltag.h"
|
||||
#include "apriltag_pose.h"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
static Eigen::Matrix3d OrthogonalizeRotationMatrix(
|
||||
const Eigen::Matrix3d& input) {
|
||||
@@ -42,14 +42,14 @@ static Eigen::Matrix3d OrthogonalizeRotationMatrix(
|
||||
return Q;
|
||||
}
|
||||
|
||||
static Transform3d MakePose(const apriltag_pose_t& pose) {
|
||||
static wpi::math::Transform3d MakePose(const apriltag_pose_t& pose) {
|
||||
if (!pose.R || !pose.t) {
|
||||
return {};
|
||||
}
|
||||
return {Translation3d{units::meter_t{pose.t->data[0]},
|
||||
units::meter_t{pose.t->data[1]},
|
||||
units::meter_t{pose.t->data[2]}},
|
||||
Rotation3d{OrthogonalizeRotationMatrix(
|
||||
return {wpi::math::Translation3d{wpi::units::meter_t{pose.t->data[0]},
|
||||
wpi::units::meter_t{pose.t->data[1]},
|
||||
wpi::units::meter_t{pose.t->data[2]}},
|
||||
wpi::math::Rotation3d{OrthogonalizeRotationMatrix(
|
||||
Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>>{
|
||||
pose.R->data})}};
|
||||
}
|
||||
@@ -80,7 +80,7 @@ static apriltag_detection_t MakeBasicDet(
|
||||
return detection;
|
||||
}
|
||||
|
||||
static Transform3d DoEstimateHomography(
|
||||
static wpi::math::Transform3d DoEstimateHomography(
|
||||
const apriltag_detection_t* detection,
|
||||
const AprilTagPoseEstimator::Config& config) {
|
||||
auto info = MakeDetectionInfo(detection, config);
|
||||
@@ -89,13 +89,13 @@ static Transform3d DoEstimateHomography(
|
||||
return MakePose(pose);
|
||||
}
|
||||
|
||||
Transform3d AprilTagPoseEstimator::EstimateHomography(
|
||||
wpi::math::Transform3d AprilTagPoseEstimator::EstimateHomography(
|
||||
const AprilTagDetection& detection) const {
|
||||
return DoEstimateHomography(
|
||||
reinterpret_cast<const apriltag_detection_t*>(&detection), m_config);
|
||||
}
|
||||
|
||||
Transform3d AprilTagPoseEstimator::EstimateHomography(
|
||||
wpi::math::Transform3d AprilTagPoseEstimator::EstimateHomography(
|
||||
std::span<const double, 9> homography) const {
|
||||
auto detection = MakeBasicDet(homography, nullptr);
|
||||
auto rv = DoEstimateHomography(&detection, m_config);
|
||||
@@ -130,7 +130,7 @@ AprilTagPoseEstimate AprilTagPoseEstimator::EstimateOrthogonalIteration(
|
||||
return rv;
|
||||
}
|
||||
|
||||
static Transform3d DoEstimate(const apriltag_detection_t* detection,
|
||||
static wpi::math::Transform3d DoEstimate(const apriltag_detection_t* detection,
|
||||
const AprilTagPoseEstimator::Config& config) {
|
||||
auto info = MakeDetectionInfo(detection, config);
|
||||
apriltag_pose_t pose;
|
||||
@@ -138,13 +138,13 @@ static Transform3d DoEstimate(const apriltag_detection_t* detection,
|
||||
return MakePose(pose);
|
||||
}
|
||||
|
||||
Transform3d AprilTagPoseEstimator::Estimate(
|
||||
wpi::math::Transform3d AprilTagPoseEstimator::Estimate(
|
||||
const AprilTagDetection& detection) const {
|
||||
return DoEstimate(reinterpret_cast<const apriltag_detection_t*>(&detection),
|
||||
m_config);
|
||||
}
|
||||
|
||||
Transform3d AprilTagPoseEstimator::Estimate(
|
||||
wpi::math::Transform3d AprilTagPoseEstimator::Estimate(
|
||||
std::span<const double, 9> homography,
|
||||
std::span<const double, 8> corners) const {
|
||||
auto detection = MakeBasicDet(homography, &corners);
|
||||
|
||||
@@ -16,8 +16,8 @@
|
||||
#include "wpi/apriltag/AprilTagDetector.hpp"
|
||||
#include "wpi/apriltag/AprilTagPoseEstimator.hpp"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::java;
|
||||
using namespace wpi::apriltag;
|
||||
using namespace wpi::util::java;
|
||||
|
||||
static JavaVM* jvm = nullptr;
|
||||
|
||||
@@ -162,7 +162,7 @@ static AprilTagDetector::QuadThresholdParameters FromJavaDetectorQTP(
|
||||
return {
|
||||
FIELD(int, Int, minClusterPixels),
|
||||
FIELD(int, Int, maxNumMaxima),
|
||||
.criticalAngle = units::radian_t{static_cast<double>(
|
||||
.criticalAngle = wpi::units::radian_t{static_cast<double>(
|
||||
env->GetDoubleField(jparams, criticalAngleField))},
|
||||
FIELD(float, Float, maxLineFitMSE),
|
||||
FIELD(int, Int, minWhiteBlackDiff),
|
||||
@@ -256,7 +256,7 @@ static jobject MakeJObject(
|
||||
static_cast<jboolean>(params.deglitch));
|
||||
}
|
||||
|
||||
static jobject MakeJObject(JNIEnv* env, const Translation3d& xlate) {
|
||||
static jobject MakeJObject(JNIEnv* env, const wpi::math::Translation3d& xlate) {
|
||||
static jmethodID constructor =
|
||||
env->GetMethodID(translation3dCls, "<init>", "(DDD)V");
|
||||
if (!constructor) {
|
||||
@@ -268,7 +268,7 @@ static jobject MakeJObject(JNIEnv* env, const Translation3d& xlate) {
|
||||
static_cast<jdouble>(xlate.Y()), static_cast<jdouble>(xlate.Z()));
|
||||
}
|
||||
|
||||
static jobject MakeJObject(JNIEnv* env, const Quaternion& q) {
|
||||
static jobject MakeJObject(JNIEnv* env, const wpi::math::Quaternion& q) {
|
||||
static jmethodID constructor =
|
||||
env->GetMethodID(quaternionCls, "<init>", "(DDDD)V");
|
||||
if (!constructor) {
|
||||
@@ -281,7 +281,7 @@ static jobject MakeJObject(JNIEnv* env, const Quaternion& q) {
|
||||
static_cast<jdouble>(q.Z()));
|
||||
}
|
||||
|
||||
static jobject MakeJObject(JNIEnv* env, const Rotation3d& rot) {
|
||||
static jobject MakeJObject(JNIEnv* env, const wpi::math::Rotation3d& rot) {
|
||||
static jmethodID constructor = env->GetMethodID(
|
||||
rotation3dCls, "<init>", "(Lorg/wpilib/math/geometry/Quaternion;)V");
|
||||
if (!constructor) {
|
||||
@@ -292,7 +292,7 @@ static jobject MakeJObject(JNIEnv* env, const Rotation3d& rot) {
|
||||
return env->NewObject(rotation3dCls, constructor, q.obj());
|
||||
}
|
||||
|
||||
static jobject MakeJObject(JNIEnv* env, const Transform3d& xform) {
|
||||
static jobject MakeJObject(JNIEnv* env, const wpi::math::Transform3d& xform) {
|
||||
static jmethodID constructor =
|
||||
env->GetMethodID(transform3dCls, "<init>",
|
||||
"(Lorg/wpilib/math/geometry/Translation3d;"
|
||||
@@ -517,7 +517,7 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePoseHomography
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy});
|
||||
AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
|
||||
return MakeJObject(env, estimator.EstimateHomography(harr));
|
||||
}
|
||||
|
||||
@@ -553,7 +553,7 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePoseOrthogonalIteration
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy});
|
||||
AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
|
||||
return MakeJObject(env,
|
||||
estimator.EstimateOrthogonalIteration(harr, carr, nIters));
|
||||
}
|
||||
@@ -590,7 +590,7 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePose
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy});
|
||||
AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
|
||||
return MakeJObject(env, estimator.Estimate(harr, carr));
|
||||
}
|
||||
|
||||
@@ -603,13 +603,13 @@ JNIEXPORT void JNICALL
|
||||
Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_generate16h5AprilTagImage
|
||||
(JNIEnv* env, jclass, jobject frameObj, jlong framePtr, jint id)
|
||||
{
|
||||
auto* frame = reinterpret_cast<wpi::RawFrame*>(framePtr);
|
||||
auto* frame = reinterpret_cast<wpi::util::RawFrame*>(framePtr);
|
||||
if (!frame) {
|
||||
nullPointerEx.Throw(env, "frame is null");
|
||||
return;
|
||||
}
|
||||
bool newData = AprilTag::Generate16h5AprilTagImage(frame, id);
|
||||
wpi::SetFrameData(env, rawFrameCls, frameObj, *frame, newData);
|
||||
wpi::util::SetFrameData(env, rawFrameCls, frameObj, *frame, newData);
|
||||
}
|
||||
|
||||
/*
|
||||
@@ -621,14 +621,14 @@ JNIEXPORT void JNICALL
|
||||
Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_generate36h11AprilTagImage
|
||||
(JNIEnv* env, jclass, jobject frameObj, jlong framePtr, jint id)
|
||||
{
|
||||
auto* frame = reinterpret_cast<wpi::RawFrame*>(framePtr);
|
||||
auto* frame = reinterpret_cast<wpi::util::RawFrame*>(framePtr);
|
||||
if (!frame) {
|
||||
nullPointerEx.Throw(env, "frame is null");
|
||||
return;
|
||||
}
|
||||
// function might reallocate
|
||||
bool newData = AprilTag::Generate36h11AprilTagImage(frame, id);
|
||||
wpi::SetFrameData(env, rawFrameCls, frameObj, *frame, newData);
|
||||
wpi::util::SetFrameData(env, rawFrameCls, frameObj, *frame, newData);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/SymbolExports.hpp"
|
||||
#include "wpi/util/json_fwd.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
/**
|
||||
* Represents an AprilTag's metadata.
|
||||
@@ -19,18 +19,18 @@ struct WPILIB_DLLEXPORT AprilTag {
|
||||
int ID;
|
||||
|
||||
/// The tag's pose.
|
||||
Pose3d pose;
|
||||
wpi::math::Pose3d pose;
|
||||
|
||||
bool operator==(const AprilTag&) const = default;
|
||||
|
||||
static bool Generate36h11AprilTagImage(wpi::RawFrame* frame, int id);
|
||||
static bool Generate16h5AprilTagImage(wpi::RawFrame* frame, int id);
|
||||
static bool Generate36h11AprilTagImage(wpi::util::RawFrame* frame, int id);
|
||||
static bool Generate16h5AprilTagImage(wpi::util::RawFrame* frame, int id);
|
||||
};
|
||||
|
||||
WPILIB_DLLEXPORT
|
||||
void to_json(wpi::json& json, const AprilTag& apriltag);
|
||||
void to_json(wpi::util::json& json, const AprilTag& apriltag);
|
||||
|
||||
WPILIB_DLLEXPORT
|
||||
void from_json(const wpi::json& json, AprilTag& apriltag);
|
||||
void from_json(const wpi::util::json& json, AprilTag& apriltag);
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -13,7 +13,7 @@
|
||||
|
||||
#include "wpi/util/SymbolExports.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
/**
|
||||
* A detection of an AprilTag tag.
|
||||
@@ -158,4 +158,4 @@ class WPILIB_DLLEXPORT AprilTagDetection final {
|
||||
double p[4][2];
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -16,7 +16,7 @@
|
||||
#include "wpi/util/StringMap.hpp"
|
||||
#include "wpi/util/SymbolExports.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
/**
|
||||
* An AprilTag detector engine. This is expensive to set up and tear down, so
|
||||
@@ -98,7 +98,7 @@ class WPILIB_DLLEXPORT AprilTagDetector {
|
||||
* angles that are close to straight or close to 180 degrees. Zero means
|
||||
* that no quads are rejected. Default is 45 degrees.
|
||||
*/
|
||||
units::radian_t criticalAngle = 45_deg;
|
||||
wpi::units::radian_t criticalAngle = 45_deg;
|
||||
|
||||
/**
|
||||
* When fitting lines to the contours, the maximum mean squared error
|
||||
@@ -254,8 +254,8 @@ class WPILIB_DLLEXPORT AprilTagDetector {
|
||||
void DestroyFamily(std::string_view name, void* data);
|
||||
|
||||
void* m_impl;
|
||||
wpi::StringMap<void*> m_families;
|
||||
units::radian_t m_qtpCriticalAngle = 10_deg;
|
||||
wpi::util::StringMap<void*> m_families;
|
||||
wpi::units::radian_t m_qtpCriticalAngle = 10_deg;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -8,11 +8,11 @@
|
||||
|
||||
#include "wpi/apriltag/AprilTagDetector.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
inline AprilTagDetector::Results AprilTagDetect(AprilTagDetector& detector,
|
||||
cv::Mat& image) {
|
||||
return detector.Detect(image.cols, image.rows, image.data);
|
||||
}
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -16,14 +16,14 @@
|
||||
#include "wpi/util/SymbolExports.hpp"
|
||||
#include "wpi/util/json_fwd.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
/**
|
||||
* Class for representing a layout of AprilTags on a field and reading them from
|
||||
* a JSON format.
|
||||
*
|
||||
* The JSON format contains two top-level objects, "tags" and "field".
|
||||
* The "tags" object is a list of all AprilTags contained within a layout. Each
|
||||
* AprilTag serializes to a JSON object containing an ID and a Pose3d. The
|
||||
* AprilTag serializes to a JSON object containing an ID and a wpi::math::Pose3d. The
|
||||
* "field" object is a descriptor of the size of the field in meters with
|
||||
* "width" and "length" values. This is to account for arbitrary field sizes
|
||||
* when transforming the poses.
|
||||
@@ -73,19 +73,19 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout {
|
||||
* @param fieldWidth Width of field the layout is representing.
|
||||
*/
|
||||
AprilTagFieldLayout(std::vector<AprilTag> apriltags,
|
||||
units::meter_t fieldLength, units::meter_t fieldWidth);
|
||||
wpi::units::meter_t fieldLength, wpi::units::meter_t fieldWidth);
|
||||
|
||||
/**
|
||||
* Returns the length of the field the layout is representing.
|
||||
* @return length
|
||||
*/
|
||||
units::meter_t GetFieldLength() const;
|
||||
wpi::units::meter_t GetFieldLength() const;
|
||||
|
||||
/**
|
||||
* Returns the length of the field the layout is representing.
|
||||
* @return width
|
||||
*/
|
||||
units::meter_t GetFieldWidth() const;
|
||||
wpi::units::meter_t GetFieldWidth() const;
|
||||
|
||||
/**
|
||||
* Returns a vector of all the april tags used in this layout.
|
||||
@@ -112,13 +112,13 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout {
|
||||
*
|
||||
* @param origin The new origin for tag transformations
|
||||
*/
|
||||
void SetOrigin(const Pose3d& origin);
|
||||
void SetOrigin(const wpi::math::Pose3d& origin);
|
||||
|
||||
/**
|
||||
* Returns the origin used for tag pose transformation.
|
||||
* @return the origin
|
||||
*/
|
||||
Pose3d GetOrigin() const;
|
||||
wpi::math::Pose3d GetOrigin() const;
|
||||
|
||||
/**
|
||||
* Gets an AprilTag pose by its ID.
|
||||
@@ -127,7 +127,7 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout {
|
||||
* @return The pose corresponding to the ID that was passed in or an empty
|
||||
* optional if a tag with that ID is not found.
|
||||
*/
|
||||
std::optional<Pose3d> GetTagPose(int ID) const;
|
||||
std::optional<wpi::math::Pose3d> GetTagPose(int ID) const;
|
||||
|
||||
/**
|
||||
* Serializes an AprilTagFieldLayout to a JSON file.
|
||||
@@ -143,22 +143,22 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout {
|
||||
|
||||
private:
|
||||
std::unordered_map<int, AprilTag> m_apriltags;
|
||||
units::meter_t m_fieldLength;
|
||||
units::meter_t m_fieldWidth;
|
||||
Pose3d m_origin;
|
||||
wpi::units::meter_t m_fieldLength;
|
||||
wpi::units::meter_t m_fieldWidth;
|
||||
wpi::math::Pose3d m_origin;
|
||||
|
||||
friend WPILIB_DLLEXPORT void to_json(wpi::json& json,
|
||||
friend WPILIB_DLLEXPORT void to_json(wpi::util::json& json,
|
||||
const AprilTagFieldLayout& layout);
|
||||
|
||||
friend WPILIB_DLLEXPORT void from_json(const wpi::json& json,
|
||||
friend WPILIB_DLLEXPORT void from_json(const wpi::util::json& json,
|
||||
AprilTagFieldLayout& layout);
|
||||
};
|
||||
|
||||
WPILIB_DLLEXPORT
|
||||
void to_json(wpi::json& json, const AprilTagFieldLayout& layout);
|
||||
void to_json(wpi::util::json& json, const AprilTagFieldLayout& layout);
|
||||
|
||||
WPILIB_DLLEXPORT
|
||||
void from_json(const wpi::json& json, AprilTagFieldLayout& layout);
|
||||
void from_json(const wpi::util::json& json, AprilTagFieldLayout& layout);
|
||||
|
||||
/**
|
||||
* Loads an AprilTagFieldLayout from a predefined field
|
||||
@@ -171,4 +171,4 @@ void from_json(const wpi::json& json, AprilTagFieldLayout& layout);
|
||||
WPILIB_DLLEXPORT AprilTagFieldLayout
|
||||
LoadAprilTagLayoutField(AprilTagField field);
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
|
||||
#include "wpi/util/SymbolExports.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
/**
|
||||
* Loadable AprilTag field layouts.
|
||||
@@ -32,4 +32,4 @@ enum class AprilTagField {
|
||||
kNumFields,
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -7,15 +7,15 @@
|
||||
#include "wpi/math/geometry/Transform3d.hpp"
|
||||
#include "wpi/util/SymbolExports.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
/** A pair of AprilTag pose estimates. */
|
||||
struct WPILIB_DLLEXPORT AprilTagPoseEstimate {
|
||||
/** Pose 1. */
|
||||
Transform3d pose1;
|
||||
wpi::math::Transform3d pose1;
|
||||
|
||||
/** Pose 2. */
|
||||
Transform3d pose2;
|
||||
wpi::math::Transform3d pose2;
|
||||
|
||||
/** Object-space error of pose 1. */
|
||||
double error1;
|
||||
@@ -32,4 +32,4 @@ struct WPILIB_DLLEXPORT AprilTagPoseEstimate {
|
||||
double GetAmbiguity() const;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
#include "wpi/units/length.hpp"
|
||||
#include "wpi/util/SymbolExports.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
class AprilTagDetection;
|
||||
|
||||
@@ -23,7 +23,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator {
|
||||
bool operator==(const Config&) const = default;
|
||||
|
||||
/** The tag size. */
|
||||
units::meter_t tagSize;
|
||||
wpi::units::meter_t tagSize;
|
||||
|
||||
/** Camera horizontal focal length, in pixels. */
|
||||
double fx;
|
||||
@@ -65,7 +65,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator {
|
||||
* @param detection Tag detection
|
||||
* @return Pose estimate
|
||||
*/
|
||||
Transform3d EstimateHomography(const AprilTagDetection& detection) const;
|
||||
wpi::math::Transform3d EstimateHomography(const AprilTagDetection& detection) const;
|
||||
|
||||
/**
|
||||
* Estimates the pose of the tag using the homography method described in [1].
|
||||
@@ -73,7 +73,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator {
|
||||
* @param homography Homography 3x3 matrix data
|
||||
* @return Pose estimate
|
||||
*/
|
||||
Transform3d EstimateHomography(std::span<const double, 9> homography) const;
|
||||
wpi::math::Transform3d EstimateHomography(std::span<const double, 9> homography) const;
|
||||
|
||||
/**
|
||||
* Estimates the pose of the tag. This returns one or two possible poses for
|
||||
@@ -123,7 +123,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator {
|
||||
* @param detection Tag detection
|
||||
* @return Pose estimate
|
||||
*/
|
||||
Transform3d Estimate(const AprilTagDetection& detection) const;
|
||||
wpi::math::Transform3d Estimate(const AprilTagDetection& detection) const;
|
||||
|
||||
/**
|
||||
* Estimates tag pose. This method is an easier to use interface to
|
||||
@@ -134,11 +134,11 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator {
|
||||
* @param corners Corner point array (X and Y for each corner in order)
|
||||
* @return Pose estimate
|
||||
*/
|
||||
Transform3d Estimate(std::span<const double, 9> homography,
|
||||
wpi::math::Transform3d Estimate(std::span<const double, 9> homography,
|
||||
std::span<const double, 8> corners) const;
|
||||
|
||||
private:
|
||||
Config m_config;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
@@ -4,7 +4,7 @@ functions:
|
||||
from_json:
|
||||
ignore: true
|
||||
classes:
|
||||
frc::AprilTag:
|
||||
wpi::apriltag::AprilTag:
|
||||
attributes:
|
||||
ID:
|
||||
pose:
|
||||
|
||||
@@ -2,7 +2,7 @@ extra_includes:
|
||||
- pybind11/eigen.h
|
||||
|
||||
classes:
|
||||
frc::AprilTagDetection:
|
||||
wpi::apriltag::AprilTagDetection:
|
||||
methods:
|
||||
GetFamily:
|
||||
GetId:
|
||||
@@ -18,7 +18,7 @@ classes:
|
||||
return py::str("<AprilTagDetection tag_family={} tag_id={} hamming={} decision_margin={} center={}>")
|
||||
.format(self.GetFamily(), self.GetId(), self.GetHamming(), self.GetDecisionMargin(), self.GetCenter());
|
||||
})
|
||||
frc::AprilTagDetection::Point:
|
||||
wpi::apriltag::AprilTagDetection::Point:
|
||||
attributes:
|
||||
x:
|
||||
y:
|
||||
|
||||
@@ -2,7 +2,7 @@ extra_includes:
|
||||
- pybind11_typing.h
|
||||
|
||||
classes:
|
||||
frc::AprilTagDetector:
|
||||
wpi::apriltag::AprilTagDetector:
|
||||
methods:
|
||||
AprilTagDetector:
|
||||
SetConfig:
|
||||
@@ -59,7 +59,7 @@ classes:
|
||||
:return: list of results
|
||||
)doc"
|
||||
)
|
||||
frc::AprilTagDetector::Config:
|
||||
wpi::apriltag::AprilTagDetector::Config:
|
||||
attributes:
|
||||
numThreads:
|
||||
quadDecimate:
|
||||
@@ -69,7 +69,7 @@ classes:
|
||||
debug:
|
||||
methods:
|
||||
operator==:
|
||||
frc::AprilTagDetector::QuadThresholdParameters:
|
||||
wpi::apriltag::AprilTagDetector::QuadThresholdParameters:
|
||||
attributes:
|
||||
minClusterPixels:
|
||||
maxNumMaxima:
|
||||
@@ -79,7 +79,7 @@ classes:
|
||||
deglitch:
|
||||
methods:
|
||||
operator==:
|
||||
frc::AprilTagDetector::Results:
|
||||
wpi::apriltag::AprilTagDetector::Results:
|
||||
rename: _Results
|
||||
ignored_bases:
|
||||
- std::span<const AprilTagDetection* const>
|
||||
|
||||
@@ -6,7 +6,7 @@ functions:
|
||||
LoadAprilTagLayoutField:
|
||||
ignore: true
|
||||
classes:
|
||||
frc::AprilTagFieldLayout:
|
||||
wpi::apriltag::AprilTagFieldLayout:
|
||||
enums:
|
||||
OriginPosition:
|
||||
methods:
|
||||
@@ -14,7 +14,7 @@ classes:
|
||||
overloads:
|
||||
'':
|
||||
std::string_view:
|
||||
std::vector<AprilTag>, units::meter_t, units::meter_t:
|
||||
std::vector<AprilTag>, wpi::units::meter_t, wpi::units::meter_t:
|
||||
LoadField:
|
||||
GetFieldLength:
|
||||
GetFieldWidth:
|
||||
@@ -22,7 +22,7 @@ classes:
|
||||
SetOrigin:
|
||||
overloads:
|
||||
OriginPosition:
|
||||
const Pose3d&:
|
||||
const wpi::math::Pose3d&:
|
||||
GetOrigin:
|
||||
GetTagPose:
|
||||
Serialize:
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
classes:
|
||||
frc::AprilTagPoseEstimate:
|
||||
wpi::apriltag::AprilTagPoseEstimate:
|
||||
attributes:
|
||||
pose1:
|
||||
pose2:
|
||||
|
||||
@@ -2,7 +2,7 @@ extra_includes:
|
||||
- wpi/apriltag/AprilTagDetection.hpp
|
||||
|
||||
classes:
|
||||
frc::AprilTagPoseEstimator:
|
||||
wpi::apriltag::AprilTagPoseEstimator:
|
||||
methods:
|
||||
AprilTagPoseEstimator:
|
||||
SetConfig:
|
||||
@@ -19,7 +19,7 @@ classes:
|
||||
overloads:
|
||||
const AprilTagDetection& [const]:
|
||||
std::span<const double, 9>, std::span<const double, 8> [const]:
|
||||
frc::AprilTagPoseEstimator::Config:
|
||||
wpi::apriltag::AprilTagPoseEstimator::Config:
|
||||
force_no_default_constructor: true
|
||||
attributes:
|
||||
tagSize:
|
||||
@@ -30,7 +30,7 @@ classes:
|
||||
methods:
|
||||
operator==:
|
||||
inline_code: |
|
||||
.def(py::init([](units::meter_t tagSize, double fx, double fy, double cx, double cy) {
|
||||
.def(py::init([](wpi::units::meter_t tagSize, double fx, double fy, double cx, double cy) {
|
||||
AprilTagPoseEstimator::Config cfg{tagSize, fx, fy, cx, cy};
|
||||
return std::make_unique<AprilTagPoseEstimator::Config>(std::move(cfg));
|
||||
}), py::arg("tagSize"), py::arg("fx"), py::arg("fy"), py::arg("cx"), py::arg("cy"))
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "wpi/apriltag/AprilTagDetector.hpp"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
TEST(AprilTagDetectorTest, ConfigDefaults) {
|
||||
AprilTagDetector detector;
|
||||
|
||||
@@ -11,17 +11,17 @@
|
||||
#include "wpi/math/geometry/Pose3d.hpp"
|
||||
#include "wpi/util/json.hpp"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
TEST(AprilTagJsonTest, DeserializeMatches) {
|
||||
auto layout = AprilTagFieldLayout{
|
||||
std::vector{
|
||||
AprilTag{1, Pose3d{}},
|
||||
AprilTag{3, Pose3d{0_m, 1_m, 0_m, Rotation3d{0_deg, 0_deg, 0_deg}}}},
|
||||
AprilTag{1, wpi::math::Pose3d{}},
|
||||
AprilTag{3, wpi::math::Pose3d{0_m, 1_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}}},
|
||||
54_ft, 27_ft};
|
||||
|
||||
AprilTagFieldLayout deserialized;
|
||||
wpi::json json = layout;
|
||||
wpi::util::json json = layout;
|
||||
EXPECT_NO_THROW(deserialized = json.get<AprilTagFieldLayout>());
|
||||
EXPECT_EQ(layout, deserialized);
|
||||
}
|
||||
|
||||
@@ -11,23 +11,23 @@
|
||||
#include "wpi/math/geometry/Pose3d.hpp"
|
||||
#include "wpi/util/json.hpp"
|
||||
|
||||
using namespace frc;
|
||||
using namespace wpi::apriltag;
|
||||
|
||||
TEST(AprilTagPoseSetOriginTest, TransformationMatches) {
|
||||
auto layout = AprilTagFieldLayout{
|
||||
std::vector<AprilTag>{
|
||||
AprilTag{1,
|
||||
Pose3d{0_ft, 0_ft, 0_ft, Rotation3d{0_deg, 0_deg, 0_deg}}},
|
||||
wpi::math::Pose3d{0_ft, 0_ft, 0_ft, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}},
|
||||
AprilTag{
|
||||
2, Pose3d{4_ft, 4_ft, 4_ft, Rotation3d{0_deg, 0_deg, 180_deg}}}},
|
||||
2, wpi::math::Pose3d{4_ft, 4_ft, 4_ft, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}}},
|
||||
54_ft, 27_ft};
|
||||
|
||||
layout.SetOrigin(
|
||||
AprilTagFieldLayout::OriginPosition::kRedAllianceWallRightSide);
|
||||
|
||||
auto mirrorPose =
|
||||
Pose3d{54_ft, 27_ft, 0_ft, Rotation3d{0_deg, 0_deg, 180_deg}};
|
||||
wpi::math::Pose3d{54_ft, 27_ft, 0_ft, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}};
|
||||
EXPECT_EQ(mirrorPose, *layout.GetTagPose(1));
|
||||
mirrorPose = Pose3d{50_ft, 23_ft, 4_ft, Rotation3d{0_deg, 0_deg, 0_deg}};
|
||||
mirrorPose = wpi::math::Pose3d{50_ft, 23_ft, 4_ft, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}};
|
||||
EXPECT_EQ(mirrorPose, *layout.GetTagPose(2));
|
||||
}
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/apriltag/AprilTagFieldLayout.hpp"
|
||||
#include "wpi/apriltag/AprilTagFields.hpp"
|
||||
|
||||
namespace frc {
|
||||
namespace wpi::apriltag {
|
||||
|
||||
std::vector<AprilTagField> GetAllFields() {
|
||||
std::vector<AprilTagField> output;
|
||||
@@ -27,21 +27,21 @@ TEST(AprilTagFieldsTest, TestLoad2022RapidReact) {
|
||||
|
||||
// Blue Hangar Truss - Hub
|
||||
auto expectedPose =
|
||||
Pose3d{127.272_in, 216.01_in, 67.932_in, Rotation3d{0_deg, 0_deg, 0_deg}};
|
||||
wpi::math::Pose3d{127.272_in, 216.01_in, 67.932_in, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}};
|
||||
auto maybePose = layout.GetTagPose(1);
|
||||
EXPECT_TRUE(maybePose);
|
||||
EXPECT_EQ(expectedPose, *maybePose);
|
||||
|
||||
// Blue Terminal Near Station
|
||||
expectedPose = Pose3d{4.768_in, 67.631_in, 35.063_in,
|
||||
Rotation3d{0_deg, 0_deg, 46.25_deg}};
|
||||
expectedPose = wpi::math::Pose3d{4.768_in, 67.631_in, 35.063_in,
|
||||
wpi::math::Rotation3d{0_deg, 0_deg, 46.25_deg}};
|
||||
maybePose = layout.GetTagPose(5);
|
||||
EXPECT_TRUE(maybePose);
|
||||
EXPECT_EQ(expectedPose, *maybePose);
|
||||
|
||||
// Upper Hub Blue-Near
|
||||
expectedPose = Pose3d{332.321_in, 183.676_in, 95.186_in,
|
||||
Rotation3d{0_deg, 26.75_deg, 69_deg}};
|
||||
expectedPose = wpi::math::Pose3d{332.321_in, 183.676_in, 95.186_in,
|
||||
wpi::math::Rotation3d{0_deg, 26.75_deg, 69_deg}};
|
||||
maybePose = layout.GetTagPose(53);
|
||||
EXPECT_TRUE(maybePose);
|
||||
EXPECT_EQ(expectedPose, *maybePose);
|
||||
@@ -62,4 +62,4 @@ TEST_P(AllFieldsFixtureTest, CheckEntireEnum) {
|
||||
INSTANTIATE_TEST_SUITE_P(ValuesEnumTestInstTests, AllFieldsFixtureTest,
|
||||
::testing::ValuesIn(GetAllFields()));
|
||||
|
||||
} // namespace frc
|
||||
} // namespace wpi::apriltag
|
||||
|
||||
Reference in New Issue
Block a user