mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
Auto-generate packet dataclasses with Jinja (#1374)
This commit is contained in:
@@ -13,6 +13,16 @@ repositories {
|
||||
|
||||
apply from: "${rootDir}/../shared/examples_common.gradle"
|
||||
|
||||
ext {
|
||||
wpilibVersion = "2025.0.0-alpha-1"
|
||||
wpimathVersion = wpilibVersion
|
||||
openCVversion = "4.8.0-2"
|
||||
}
|
||||
|
||||
wpi.getVersions().getOpencvVersion().convention(openCVversion);
|
||||
wpi.getVersions().getWpilibVersion().convention(wpilibVersion);
|
||||
wpi.getVersions().getWpimathVersion().convention(wpimathVersion);
|
||||
|
||||
// Define my targets (RoboRIO) and artifacts (deployable files)
|
||||
// This is added by GradleRIO's backing project DeployUtils.
|
||||
deploy {
|
||||
@@ -58,36 +68,21 @@ wpi.sim.addDriverstation()
|
||||
model {
|
||||
components {
|
||||
frcUserProgram(NativeExecutableSpec) {
|
||||
// We don't need to build for roborio -- if we do, we need to install
|
||||
// a roborio toolchain every time we build in CI
|
||||
// Ideally, we'd be able to set the roborio toolchain as optional, but
|
||||
// I can't figure out how to set that environment variable from build.gradle
|
||||
// (see https://github.com/wpilibsuite/native-utils/blob/2917c69fb5094e36d499c465f047dab81c68446c/ToolchainPlugin/src/main/java/edu/wpi/first/toolchain/ToolchainGraphBuildService.java#L71)
|
||||
// for now, commented out
|
||||
|
||||
// targetPlatform wpi.platforms.roborio
|
||||
|
||||
if (includeDesktopSupport) {
|
||||
targetPlatform wpi.platforms.desktop
|
||||
}
|
||||
targetPlatform wpi.platforms.roborio
|
||||
targetPlatform wpi.platforms.desktop
|
||||
|
||||
sources.cpp {
|
||||
source {
|
||||
srcDir 'src/main/cpp'
|
||||
include '**/*.cpp', '**/*.cc'
|
||||
}
|
||||
exportedHeaders {
|
||||
srcDir 'src/main/include'
|
||||
}
|
||||
}
|
||||
|
||||
// Set deploy task to deploy this component
|
||||
deployArtifact.component = it
|
||||
|
||||
// Enable run tasks for this component
|
||||
wpi.cpp.enableExternalTasks(it)
|
||||
|
||||
// Enable simulation for this component
|
||||
wpi.sim.enable(it)
|
||||
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
|
||||
wpi.cpp.vendor.cpp(it)
|
||||
@@ -105,7 +100,6 @@ model {
|
||||
}
|
||||
}
|
||||
|
||||
// Enable run tasks for this component
|
||||
wpi.cpp.enableExternalTasks(it)
|
||||
|
||||
wpi.cpp.vendor.cpp(it)
|
||||
|
||||
@@ -26,6 +26,22 @@
|
||||
|
||||
#include <photon/PhotonUtils.h>
|
||||
|
||||
#include <frc/Timer.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <units/time.h>
|
||||
|
||||
void Robot::RobotPeriodic() {
|
||||
photon::PhotonCamera::SetVersionCheckEnabled(false);
|
||||
|
||||
auto start = frc::Timer::GetFPGATimestamp();
|
||||
photon::PhotonPipelineResult result = camera.GetLatestResult();
|
||||
auto end = frc::Timer::GetFPGATimestamp();
|
||||
|
||||
std::printf("DT is %.2f uS for %i targets\n",
|
||||
units::microsecond_t(end - start).to<double>(),
|
||||
result.GetTargets().size());
|
||||
}
|
||||
|
||||
void Robot::TeleopPeriodic() {
|
||||
double forwardSpeed = -xboxController.GetRightY();
|
||||
double rotationSpeed;
|
||||
@@ -33,7 +49,10 @@ void Robot::TeleopPeriodic() {
|
||||
if (xboxController.GetAButton()) {
|
||||
// Vision-alignment mode
|
||||
// Query the latest result from PhotonVision
|
||||
auto start = frc::Timer::GetFPGATimestamp();
|
||||
photon::PhotonPipelineResult result = camera.GetLatestResult();
|
||||
auto end = frc::Timer::GetFPGATimestamp();
|
||||
frc::SmartDashboard::PutNumber("decode_dt", (end - start).to<double>());
|
||||
|
||||
if (result.HasTargets()) {
|
||||
// Rotation speed is the output of the PID controller
|
||||
|
||||
@@ -37,10 +37,11 @@
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void TeleopPeriodic() override;
|
||||
void RobotPeriodic() override;
|
||||
|
||||
private:
|
||||
// Change this to match the name of your camera as shown in the web UI
|
||||
photon::PhotonCamera camera{"YOUR_CAMERA_NAME_HERE"};
|
||||
photon::PhotonCamera camera{"WPI2024"};
|
||||
// PID constants should be tuned per robot
|
||||
frc::PIDController controller{.1, 0, 0};
|
||||
|
||||
|
||||
@@ -79,10 +79,10 @@ class Vision {
|
||||
|
||||
// In sim only, add our vision estimate to the sim debug field
|
||||
if (frc::RobotBase::IsSimulation()) {
|
||||
if (visionEst.has_value()) {
|
||||
if (visionEst) {
|
||||
GetSimDebugField()
|
||||
.GetObject("VisionEstimation")
|
||||
->SetPose(visionEst.value().estimatedPose.ToPose2d());
|
||||
->SetPose(visionEst->estimatedPose.ToPose2d());
|
||||
} else {
|
||||
GetSimDebugField().GetObject("VisionEstimation")->SetPoses({});
|
||||
}
|
||||
@@ -101,9 +101,9 @@ class Vision {
|
||||
for (const auto& tgt : targets) {
|
||||
auto tagPose =
|
||||
photonEstimator.GetFieldLayout().GetTagPose(tgt.GetFiducialId());
|
||||
if (tagPose.has_value()) {
|
||||
if (tagPose) {
|
||||
numTags++;
|
||||
avgDist += tagPose.value().ToPose2d().Translation().Distance(
|
||||
avgDist += tagPose->ToPose2d().Translation().Distance(
|
||||
estimatedPose.Translation());
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user