Make 2027 build (#2422)

This PR updates everything for 2027. This includes removing GradleRIO, simplifying our wpilib version defintion, updating APIs, updating to Java 21, and more.

Note that photonlibpy is failing because robotpy has not been fully updated yet. Examples are omitted because they need to be updated for our new PhotonPoseEstimator API and still need some changes from WPILIB. photonlib windows build is failing because we're waiting for some upstream changes. Finally, images are failing since they don't have Java 21 yet.
This commit is contained in:
Sam Freund
2026-04-11 12:14:42 -05:00
committed by samfreund
parent 4412df1516
commit 68fc1e7129
111 changed files with 630 additions and 578 deletions

View File

@@ -45,10 +45,9 @@ jobs:
# fetch-depth: 0
# - name: Fetch tags
# run: git fetch --tags --force
# - name: Install Java 17
# uses: actions/setup-java@v5
# - uses: actions/setup-java@v5
# with:
# java-version: 17
# java-version: 21
# distribution: temurin
# - name: Install SystemCore Toolchain
# run: ./gradlew installSystemCoreToolchain
@@ -104,10 +103,9 @@ jobs:
fetch-depth: 0
- name: Fetch tags
run: git fetch --tags --force
- name: Install Java 17
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
- name: Install pnpm
uses: pnpm/action-setup@v5
@@ -145,10 +143,9 @@ jobs:
fetch-depth: 0
- name: Fetch tags
run: git fetch --tags --force
- name: Install Java 17
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
- name: Install pnpm
uses: pnpm/action-setup@v5
@@ -198,10 +195,9 @@ jobs:
with:
fetch-depth: 0
- name: Install Java 17
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
# grab all tags
@@ -240,10 +236,9 @@ jobs:
- uses: actions/checkout@v6
with:
fetch-depth: 0
- name: Install Java 17
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
- run: git fetch --tags --force
- run: ./gradlew photon-targeting:build photon-lib:build
@@ -265,13 +260,13 @@ jobs:
fail-fast: false
matrix:
include:
- container: wpilib/systemcore-cross-ubuntu:2025-24.04
- container: wpilib/systemcore-cross-ubuntu:2027-24.04
artifact-name: SystemCore
build-options: "-Ponlylinuxsystemcore"
- container: wpilib/raspbian-cross-ubuntu:bookworm-24.04
- container: wpilib/raspbian-cross-ubuntu:2027-bookworm-24.04
artifact-name: Raspbian
build-options: "-Ponlylinuxarm32"
- container: wpilib/aarch64-cross-ubuntu:bookworm-24.04
- container: wpilib/aarch64-cross-ubuntu:2027-bookworm-24.04
artifact-name: Aarch64
build-options: "-Ponlylinuxarm64"
@@ -347,10 +342,9 @@ jobs:
- uses: actions/checkout@v6
with:
fetch-depth: 0
- name: Install Java 17
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
- name: Install pnpm
uses: pnpm/action-setup@v5
@@ -431,15 +425,16 @@ jobs:
artifact-name: photonvision-*-winx64.jar
- os: macos-latest
artifact-name: photonvision-*-macarm64.jar
- os: ubuntu-24.04-arm
artifact-name: photonvision-*-linuxarm64.jar
runs-on: ${{ matrix.os }}
steps:
- name: Install Java 17
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
- uses: actions/download-artifact@v8
with:

View File

@@ -13,10 +13,9 @@ jobs:
steps:
- name: Checkout sources
uses: actions/checkout@v6
- name: Setup Java
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
distribution: 'temurin'
java-version: 17
java-version: 21
- name: Generate and submit dependency graph
uses: gradle/actions/dependency-submission@v5

View File

@@ -61,7 +61,7 @@ jobs:
fetch-depth: 0
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
- run: |
set +e

View File

@@ -60,10 +60,9 @@ jobs:
fetch-depth: 0
- name: Fetch tags
run: git fetch --tags --force
- name: Install Java 17
uses: actions/setup-java@v5
- uses: actions/setup-java@v5
with:
java-version: 17
java-version: 21
distribution: temurin
- name: Build javadocs/doxygen
run: |

View File

@@ -4,12 +4,13 @@ plugins {
id "cpp"
id "com.diffplug.spotless" version "8.1.0"
id "org.wpilib.WPILibRepositoriesPlugin" version "2027.0.0"
id "org.wpilib.GradleRIO" version "2027.0.0-alpha-2"
id 'org.photonvision.tools.WpilibTools' version '2.4.1-photon'
id 'com.google.protobuf' version '0.9.3' apply false
id 'org.wpilib.NativeUtils' version '2027.4.1' apply false
id 'org.wpilib.DeployUtils' version '2027.1.0' apply false
id 'org.photonvision.tools.WpilibTools' version '3.0.0-photon'
id 'com.google.protobuf' version '0.9.5' apply false
id 'org.wpilib.GradleJni' version '2027.0.0'
id "org.ysb33r.doxygen" version "2.0.0" apply false
id 'com.gradleup.shadow' version '8.3.4' apply false
id 'com.gradleup.shadow' version '9.0.0' apply false
id "com.github.node-gradle.node" version "7.0.1" apply false
}
@@ -33,16 +34,20 @@ ext.allOutputsFolder = file("$project.buildDir/outputs")
apply from: "versioningHelper.gradle"
ext {
wpilibVersion = "2027.0.0-alpha-3-203-g0001ddc7e"
wpilibVersion = "2027.0.0-alpha-4"
wpimathVersion = wpilibVersion
openCVYear = "2025"
openCVversion = "4.10.0-3"
ejmlVersion = "0.43.1";
jacksonVersion = "2.15.2";
quickbufVersion = "1.3.3";
javalinVersion = "6.7.0"
libcameraDriverVersion = "v2026.0.0"
rknnVersion = "dev-v2026.0.1-1-g89b2888"
rubikVersion = "dev-v2026.0.1-4-g13d6279"
frcYear = "2027_alpha1"
mrcalVersion = "dev-v2026.0.0-1-g239d80e";
frcYear = "2027_alpha4"
mrcalVersion = "v2027.0.1";
pubVersion = versionString
isDev = pubVersion.startsWith("dev")
@@ -95,7 +100,7 @@ spotless {
}
wrapper {
gradleVersion = '8.14.3'
gradleVersion = '9.2.0'
}
ext.getCurrentArch = {

View File

@@ -1,6 +1,6 @@
distributionBase=GRADLE_USER_HOME
distributionPath=permwrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.14.3-bin.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-9.2.0-bin.zip
networkTimeout=10000
validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME

View File

@@ -6,7 +6,7 @@ ext.licenseFile = file("$rootDir/LICENSE")
ext.externalLicensesFolder = file("$rootDir/ExternalLicenses")
apply from: "${rootDir}/shared/common.gradle"
wpilibTools.deps.wpilibVersion = wpi.versions.wpilibVersion.get()
wpilibTools.deps.wpilibVersion = wpilibVersion
def nativeConfigName = 'wpilibNatives'
configurations {
@@ -28,7 +28,7 @@ dependencies {
wpilibNatives wpilibTools.deps.wpilib("cscore")
wpilibNatives wpilibTools.deps.wpilib("apriltag")
wpilibNatives wpilibTools.deps.wpilib("hal")
wpilibNatives wpilibTools.deps.wpilibOpenCv("frc" + openCVYear, wpi.versions.opencvVersion.get())
wpilibNatives wpilibTools.deps.wpilibOpenCv("frc" + openCVYear, openCVversion)
// These stay as implementation dependencies since they don't have native code that gets packaged
implementation 'org.zeroturnaround:zt-zip:1.14'

View File

@@ -35,6 +35,8 @@ import org.photonvision.common.logging.Logger;
import org.photonvision.common.networking.NetworkUtils;
import org.photonvision.common.util.TimedTaskManager;
import org.photonvision.common.util.file.JacksonUtils;
import org.wpilib.driverstation.Alert;
import org.wpilib.driverstation.Alert.Level;
import org.wpilib.networktables.LogMessage;
import org.wpilib.networktables.MultiSubscriber;
import org.wpilib.networktables.NetworkTable;
@@ -43,8 +45,6 @@ import org.wpilib.networktables.NetworkTableEvent.Kind;
import org.wpilib.networktables.NetworkTableInstance;
import org.wpilib.networktables.StringSubscriber;
import org.wpilib.smartdashboard.SmartDashboard;
import org.wpilib.util.Alert;
import org.wpilib.util.Alert.AlertType;
import org.wpilib.vision.apriltag.AprilTagFieldLayout;
import org.wpilib.vision.camera.CameraServerJNI;
@@ -66,9 +66,9 @@ public class NetworkTablesManager {
new MultiSubscriber(ntInstance, new String[] {kRootTableName + "/" + kCoprocTableName + "/"});
// Creating the alert up here since it should be persistent
private final Alert conflictAlert = new Alert("PhotonAlerts", "", AlertType.kWarning);
private final Alert conflictAlert = new Alert("PhotonAlerts", "", Level.MEDIUM);
private final Alert mismatchAlert = new Alert("PhotonAlerts", "", AlertType.kWarning);
private final Alert mismatchAlert = new Alert("PhotonAlerts", "", Level.MEDIUM);
public boolean conflictingHostname = false;
public String conflictingCameras = "";

View File

@@ -36,7 +36,6 @@ import org.photonvision.common.hardware.gpio.CustomDeviceFactory;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.ShellExec;
import org.photonvision.common.util.TimedTaskManager;
import org.wpilib.networktables.IntegerPublisher;
import org.wpilib.networktables.IntegerSubscriber;

View File

@@ -35,30 +35,8 @@ import org.photonvision.common.logging.Logger;
public class OsImageData {
private static final Logger logger = new Logger(OsImageData.class, LogGroup.General);
private static Path imageVersionFile = Path.of("/opt/photonvision/image-version");
private static Path imageMetadataFile = Path.of("/opt/photonvision/image-version.json");
/**
* The OS image version string, if available. This is legacy, use {@link ImageMetadata}.
* Deprecated for removal in 2027.
*/
@Deprecated public static final Optional<String> IMAGE_VERSION = getImageVersion();
private static Optional<String> getImageVersion() {
if (!imageVersionFile.toFile().exists()) {
logger.warn("Photon cannot locate base OS image version at " + imageVersionFile.toString());
return Optional.empty();
}
try {
return Optional.of(Files.readString(imageVersionFile).strip());
} catch (IOException e) {
logger.error("Couldn't read image-version file", e);
}
return Optional.empty();
}
public static final Optional<ImageMetadata> IMAGE_METADATA = getImageMetadata();
public static record ImageMetadata(

View File

@@ -28,6 +28,7 @@ import org.opencv.highgui.HighGui;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.pipeline.result.CVPipelineResult;
import org.photonvision.vision.target.TrackedTarget;
import org.wpilib.math.geometry.Rotation2d;
import org.wpilib.math.geometry.Translation2d;
import org.wpilib.math.util.Units;

View File

@@ -21,6 +21,7 @@ import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnore;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import java.awt.Color;
import java.nio.file.Path;
import java.util.Arrays;
import java.util.List;
@@ -29,6 +30,10 @@ import org.opencv.core.Core;
import org.opencv.core.Mat;
import org.opencv.core.Point;
import org.opencv.core.Point3;
import org.opencv.core.Scalar;
import org.opencv.imgcodecs.Imgcodecs;
import org.opencv.imgproc.Imgproc;
import org.photonvision.common.util.ColorHelper;
import org.wpilib.math.geometry.Pose3d;
// Ignore the previous calibration data that was stored in the json file.

View File

@@ -23,7 +23,6 @@ import org.photonvision.common.logging.Logger;
import org.photonvision.jni.CscoreExtras;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.processes.VisionSourceSettables;
import org.wpilib.networktables.BooleanSubscriber;
import org.wpilib.util.PixelFormat;
import org.wpilib.util.RawFrame;
import org.wpilib.vision.camera.CvSink;
@@ -81,7 +80,7 @@ public class USBFrameProvider extends CpuImageProcessor {
if (m_blockForFrames) {
// We allocate memory so we don't fill a Mat in use by another thread (memory model is easier)
var mat = new CVMat();
// This is from wpi::util::Now, or WPIUtilJNI.now(). The epoch from grabFrame is uS since
// This is from wpi::nt::Now, or WPIUtilJNI.now(). The epoch from grabFrame is uS since
// Hal::initialize was called
// TODO - under the hood, this incurs an extra copy. We should avoid this, if we
// can.
@@ -106,7 +105,7 @@ public class USBFrameProvider extends CpuImageProcessor {
cameraMode.width * 3,
PixelFormat.kBGR);
// This is from wpi::util::Now, or WPIUtilJNI.now(). The epoch from grabFrame is uS since
// This is from wpi::nt::Now, or WPIUtilJNI.now(). The epoch from grabFrame is uS since
// Hal::initialize was called
long captureTimeUs =
CscoreExtras.grabRawSinkFrameTimeoutLastTime(

View File

@@ -209,7 +209,7 @@ public class AprilTagPipeline extends CVPipeline<CVPipelineResult, AprilTagPipel
camToTag =
new Transform3d(
camToTag.getTranslation(),
new Rotation3d(0, Math.PI, 0).plus(camToTag.getRotation()));
new Rotation3d(0, Math.PI, 0).rotateBy(camToTag.getRotation()));
tagPoseEstimate = new AprilTagPoseEstimate(camToTag, camToTag, 0, 0);
}
}

View File

@@ -104,7 +104,7 @@ public class CVPipelineResult implements Releasable {
}
/**
* Get the latency between now (wpi::util::Now) and the time at which the image was captured.
* Get the latency between now (wpi::nt::Now) and the time at which the image was captured.
* FOOTGUN: the latency is relative to the time at which this method is called. Waiting to call
* this method will change the latency this method returns.
*/

View File

@@ -119,7 +119,7 @@ task generateJavaDocs(type: Javadoc) {
source exportedProjects.collect { project(it).sourceSets.main.allJava }
classpath = files(exportedProjects.collect { project(it).sourceSets.main.compileClasspath })
options.links "https://docs.oracle.com/en/java/javase/17/docs/api/", "https://github.wpilib.org/allwpilib/docs/release/java/"
options.links "https://docs.oracle.com/en/java/javase/21/docs/api/", "https://github.wpilib.org/allwpilib/docs/release/java/"
options.addStringOption("tag", "pre:a:Pre-Condition")
options.addBooleanOption("Xdoclint:html,missing,reference,syntax", true)
options.addBooleanOption('html5', true)

View File

@@ -353,7 +353,7 @@ publishing {
}
// setup wpilib bundled native libs
wpilibTools.deps.wpilibVersion = wpi.versions.wpilibVersion.get()
wpilibTools.deps.wpilibVersion = wpilibVersion
def nativeConfigName = 'wpilibNatives'
def nativeConfig = configurations.create(nativeConfigName)
@@ -375,4 +375,4 @@ nativeConfig.dependencies.add wpilibTools.deps.wpilib("ntcore")
nativeConfig.dependencies.add wpilibTools.deps.wpilib("cscore")
nativeConfig.dependencies.add wpilibTools.deps.wpilib("apriltag")
nativeConfig.dependencies.add wpilibTools.deps.wpilib("hal")
nativeConfig.dependencies.add wpilibTools.deps.wpilibOpenCv("frc" + openCVYear, wpi.versions.opencvVersion.get())
nativeConfig.dependencies.add wpilibTools.deps.wpilibOpenCv("frc" + openCVYear, openCVversion)

View File

@@ -118,10 +118,7 @@ class PhotonCamera:
inst.start()
# Usage reporting
hal.report(
hal.tResourceType.kResourceType_PhotonCamera.value,
PhotonCamera.instance_count,
)
hal.reportUsage("PhotonVision/PhotonCamera", PhotonCamera.instance_count, "")
PhotonCamera.instance_count += 1
def getAllUnreadResults(self) -> List[PhotonPipelineResult]:

View File

@@ -66,9 +66,8 @@ class PhotonPoseEstimator:
self._headingBuffer = TimeInterpolatableRotation2dBuffer(1)
# Usage reporting
hal.report(
hal.tResourceType.kResourceType_PhotonPoseEstimator.value,
PhotonPoseEstimator.instance_count,
hal.reportUsage(
"PhotonVision/PhotonPoseEstimator", PhotonPoseEstimator.instance_count, ""
)
PhotonPoseEstimator.instance_count += 1

View File

@@ -33,6 +33,7 @@ import org.photonvision.common.hardware.VisionLEDMode;
import org.photonvision.common.networktables.PacketSubscriber;
import org.photonvision.targeting.PhotonPipelineResult;
import org.photonvision.timesync.TimeSyncSingleton;
import org.wpilib.driverstation.Alert;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.hardware.hal.HAL;
import org.wpilib.math.linalg.MatBuilder;
@@ -51,8 +52,6 @@ import org.wpilib.networktables.NetworkTableInstance;
import org.wpilib.networktables.PubSubOption;
import org.wpilib.networktables.StringSubscriber;
import org.wpilib.system.Timer;
import org.wpilib.util.Alert;
import org.wpilib.util.Alert.AlertType;
/** Represents a camera that is connected to PhotonVision. */
public class PhotonCamera implements AutoCloseable {
@@ -137,8 +136,8 @@ public class PhotonCamera implements AutoCloseable {
name = cameraName;
disconnectAlert =
new Alert(
PHOTON_ALERT_GROUP, "PhotonCamera '" + name + "' is disconnected.", AlertType.kWarning);
timesyncAlert = new Alert(PHOTON_ALERT_GROUP, "", AlertType.kWarning);
PHOTON_ALERT_GROUP, "PhotonCamera '" + name + "' is disconnected.", Alert.Level.MEDIUM);
timesyncAlert = new Alert(PHOTON_ALERT_GROUP, "", Alert.Level.MEDIUM);
rootPhotonTable = instance.getTable(kTableName);
this.cameraTable = rootPhotonTable.getSubTable(cameraName);
path = cameraTable.getPath();
@@ -149,7 +148,7 @@ public class PhotonCamera implements AutoCloseable {
PhotonPipelineResult.photonStruct.getTypeString(),
new byte[0],
PubSubOption.periodic(0.01),
PubSubOption.sendAll(true),
PubSubOption.SEND_ALL,
PubSubOption.pollStorage(20));
resultSubscriber = new PacketSubscriber<>(rawBytesEntry, PhotonPipelineResult.photonStruct);
driverModePublisher = cameraTable.getBooleanTopic("driverModeRequest").publish();
@@ -172,8 +171,7 @@ public class PhotonCamera implements AutoCloseable {
// Existing is enough to make this multisubscriber do its thing
topicNameSubscriber =
new MultiSubscriber(
instance, new String[] {"/photonvision/"}, PubSubOption.topicsOnly(true));
new MultiSubscriber(instance, new String[] {"/photonvision/"}, PubSubOption.TOPICS_ONLY);
InstanceCount++;
HAL.reportUsage("PhotonVision/PhotonCamera", InstanceCount, "");
@@ -576,7 +574,7 @@ public class PhotonCamera implements AutoCloseable {
// spotless:on
DriverStation.reportWarning(bfw, false);
var versionMismatchMessage =
String versionMismatchMessage =
"Photon version "
+ PhotonVersion.versionString
+ " (message definition version "

View File

@@ -152,7 +152,7 @@ public class PhotonPoseEstimator {
this.fieldTags = fieldTags;
this.robotToCamera = robotToCamera;
HAL.report(tResourceType.kResourceType_PhotonPoseEstimator, InstanceCount);
HAL.reportUsage("PhotonVision/PhotonPoseEstimator", InstanceCount, "");
InstanceCount++;
}
@@ -1140,7 +1140,7 @@ public class PhotonPoseEstimator {
double weight = (1.0 / pair.getFirst().getPoseAmbiguity()) / totalAmbiguity;
Pose3d estimatedPose = pair.getSecond();
transform = transform.plus(estimatedPose.getTranslation().times(weight));
rotation = rotation.plus(estimatedPose.getRotation().times(weight));
rotation = rotation.rotateBy(estimatedPose.getRotation().times(weight));
}
return Optional.of(

View File

@@ -531,7 +531,7 @@ public class PhotonCameraSim implements AutoCloseable {
// Simulate confidence using sqrt-scaled area for a more realistic
// curve. Raw areaPercent/100 is tiny for most targets; sqrt scaling
// gives reasonable values even for small-but-visible objects.
conf = (float) MathUtil.clamp(Math.sqrt(areaPercent / 100.0) * 2.0, 0.0, 1.0);
conf = (float) Math.clamp(Math.sqrt(areaPercent / 100.0) * 2.0, 0.0, 1.0);
}
detectableTgts.add(

View File

@@ -29,15 +29,16 @@
#include <string_view>
#include <vector>
#include <wpi/hal/UsageReporting.h>
#include <net/TimeSyncServer.h>
#include <opencv2/core.hpp>
#include <opencv2/core/utility.hpp>
#include <wpi/hal/UsageReporting.hpp>
#include <wpi/system/Errors.hpp>
#include <wpi/system/RobotController.hpp>
#include <wpi/system/Timer.hpp>
#include <wpi/system/WPILibVersion.hpp>
#include <wpi/util/json.hpp>
#include <wpi/util/string.hpp>
#include "PhotonVersion.h"
#include "photon/dataflow/structures/Packet.h"
@@ -164,8 +165,8 @@ PhotonCamera::PhotonCamera(wpi::nt::NetworkTableInstance instance,
disconnectAlert(PHOTON_ALERT_GROUP,
std::string{"PhotonCamera '"} + std::string{cameraName} +
"' is disconnected.",
wpi::Alert::AlertType::kWarning),
timesyncAlert(PHOTON_ALERT_GROUP, "", wpi::Alert::AlertType::kWarning) {
wpi::Alert::Level::MEDIUM),
timesyncAlert(PHOTON_ALERT_GROUP, "", wpi::Alert::Level::MEDIUM) {
verifyDependencies();
InstanceCount++;
HAL_ReportUsage("PhotonVision/PhotonCamera", InstanceCount, "");

View File

@@ -33,8 +33,7 @@
#include <opencv2/calib3d.hpp>
#include <opencv2/core/mat.hpp>
#include <opencv2/core/types.hpp>
#include <wpi/deprecated.h>
#include <wpi/hal/UsageReporting.h>
#include <wpi/hal/UsageReporting.hpp>
#include <wpi/math/geometry/Pose3d.hpp>
#include <wpi/math/geometry/Rotation3d.hpp>
#include <wpi/math/geometry/Transform3d.hpp>
@@ -42,6 +41,7 @@
#include <wpi/units/angle.hpp>
#include <wpi/units/math.hpp>
#include <wpi/units/time.hpp>
#include <wpi/util/deprecated.hpp>
#include "photon/PhotonCamera.h"
#include "photon/estimation/TargetModel.h"
@@ -74,8 +74,7 @@ PhotonPoseEstimator::PhotonPoseEstimator(
poseCacheTimestamp(-1_s),
headingBuffer(
wpi::math::TimeInterpolatableBuffer<wpi::math::Rotation2d>(1_s)) {
HAL_Report(HALUsageReporting::kResourceType_PhotonPoseEstimator,
InstanceCount);
HAL_ReportUsage("PhotonVision/PhotonPoseEstimator", InstanceCount, "");
InstanceCount++;
}
@@ -187,10 +186,8 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::Update(
}
break;
case CONSTRAINED_SOLVEPNP: {
using namespace frc;
if (!cameraMatrixData || !cameraDistCoeffs) {
WPILib_ReportError(
WPILIB_ReportError(
wpi::warn::Warning,
"No camera calibration data provided for Constrained SolvePnP!");
ret = Update(result, this->multiTagFallbackStrategy);
@@ -255,7 +252,7 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::Update(
bool ShouldEstimate(const PhotonPipelineResult& result) {
// Time in the past -- give up, since the following if expects times > 0
if (result.GetTimestamp() < 0_s) {
WPILib_ReportError(wpi::warn::Warning,
WPILIB_ReportError(wpi::warn::Warning,
"Result timestamp was reported in the past!");
return false;
}
@@ -624,7 +621,7 @@ PhotonPoseEstimator::EstimateAverageBestTargetsPose(
pair : tempPoses) {
double const weight = (1. / pair.second.first) / totalAmbiguity;
transform = transform + pair.first.Translation() * weight;
rotation = rotation + pair.first.Rotation() * weight;
rotation = rotation.RotateBy(pair.first.Rotation() * weight);
}
return EstimatedRobotPose{wpi::math::Pose3d(transform, rotation),
@@ -661,7 +658,6 @@ PhotonPoseEstimator::EstimateConstrainedSolvepnpPose(
cameraMatrix, distCoeffs, targets, m_robotToCamera, seedPose,
aprilTags, photon::kAprilTag36h11, headingFree,
wpi::math::Rotation2d{
headingBuffer.Sample(cameraResult.GetTimestamp()).value()},
headingScaleFactor);

View File

@@ -51,7 +51,7 @@ PhotonCameraSim::PhotonCameraSim(
videoSimRaw =
wpi::CameraServer::PutVideo(std::string{camera->GetCameraName()} + "-raw",
prop.GetResWidth(), prop.GetResHeight());
videoSimRaw.SetPixelFormat(wpi::cs::VideoMode::PixelFormat::kGray);
videoSimRaw.SetPixelFormat(wpi::util::PixelFormat::kGray);
videoSimProcessed = wpi::CameraServer::PutVideo(
std::string{camera->GetCameraName()} + "-processed", prop.GetResWidth(),
prop.GetResHeight());
@@ -89,14 +89,16 @@ bool PhotonCameraSim::CanSeeCorner(const std::vector<cv::Point2f>& points) {
return true;
}
std::optional<uint64_t> PhotonCameraSim::ConsumeNextEntryTime() {
uint64_t now = wpi::util::Now();
uint64_t timestamp{};
int64_t now = wpi::nt::Now();
int64_t timestamp{};
bool hasTimestamp = false;
int iter = 0;
while (now >= nextNTEntryTime) {
timestamp = nextNTEntryTime;
uint64_t frameTime = prop.EstSecUntilNextFrame()
.convert<wpi::units::microseconds>()
.to<uint64_t>();
hasTimestamp = true;
int64_t frameTime = prop.EstSecUntilNextFrame()
.convert<wpi::units::microseconds>()
.to<int64_t>();
nextNTEntryTime += frameTime;
if (iter++ > 50) {
@@ -106,8 +108,8 @@ std::optional<uint64_t> PhotonCameraSim::ConsumeNextEntryTime() {
}
}
if (timestamp != 0) {
return timestamp;
if (hasTimestamp) {
return static_cast<uint64_t>(timestamp);
} else {
return std::nullopt;
}
@@ -363,7 +365,7 @@ PhotonPipelineResult PhotonCameraSim::Process(
detectableTgts, multiTagResults};
}
void PhotonCameraSim::SubmitProcessedFrame(const PhotonPipelineResult& result) {
SubmitProcessedFrame(result, wpi::util::Now());
SubmitProcessedFrame(result, wpi::nt::Now());
}
void PhotonCameraSim::SubmitProcessedFrame(const PhotonPipelineResult& result,
uint64_t ReceiveTimestamp) {

View File

@@ -28,7 +28,7 @@
#include <utility>
#include <vector>
#include <frc/Errors.h>
#include <wpi/system/Errors.hpp>
using namespace photon;
@@ -75,32 +75,32 @@ void SimCameraProperties::SetCalibration(
1_m,
wpi::math::Rotation3d{
0_rad, 0_rad,
(GetPixelYaw(0) +
wpi::math::Rotation2d{wpi::units::radian_t{-std::numbers::pi / 2.0}})
(GetPixelYaw(0) + wpi::math::Rotation2d{wpi::units::radian_t{
-std::numbers::pi / 2.0}})
.Radians()}},
wpi::math::Translation3d{
1_m,
wpi::math::Rotation3d{
0_rad, 0_rad,
(GetPixelYaw(width) +
wpi::math::Rotation2d{wpi::units::radian_t{std::numbers::pi / 2.0}})
(GetPixelYaw(width) + wpi::math::Rotation2d{wpi::units::radian_t{
std::numbers::pi / 2.0}})
.Radians()}},
wpi::math::Translation3d{
1_m,
wpi::math::Rotation3d{
0_rad,
(GetPixelPitch(0) +
wpi::math::Rotation2d{wpi::units::radian_t{std::numbers::pi / 2.0}})
(GetPixelPitch(0) + wpi::math::Rotation2d{wpi::units::radian_t{
std::numbers::pi / 2.0}})
.Radians(),
0_rad}},
wpi::math::Translation3d{
1_m,
wpi::math::Rotation3d{
0_rad,
(GetPixelPitch(height) +
wpi::math::Rotation2d{wpi::units::radian_t{-std::numbers::pi / 2.0}})
.Radians(),
0_rad}},
wpi::math::Rotation3d{0_rad,
(GetPixelPitch(height) +
wpi::math::Rotation2d{wpi::units::radian_t{
-std::numbers::pi / 2.0}})
.Radians(),
0_rad}},
};
viewplanes.clear();
for (size_t i = 0; i < p.size(); i++) {

View File

@@ -28,6 +28,7 @@
#include <string>
#include <vector>
#include <wpi/driverstation/Alert.hpp>
#include <wpi/nt/BooleanTopic.hpp>
#include <wpi/nt/DoubleArrayTopic.hpp>
#include <wpi/nt/DoubleTopic.hpp>
@@ -38,7 +39,6 @@
#include <wpi/nt/RawTopic.hpp>
#include <wpi/nt/StringTopic.hpp>
#include <wpi/units/time.hpp>
#include <wpi/util/Alert.hpp>
#include "photon/targeting/PhotonPipelineResult.h"
@@ -204,7 +204,9 @@ class PhotonCamera {
*/
static void SetVersionCheckEnabled(bool enabled);
std::shared_ptr<wpi::nt::NetworkTable> GetCameraTable() const { return rootTable; }
std::shared_ptr<wpi::nt::NetworkTable> GetCameraTable() const {
return rootTable;
}
// For use in tests
bool test = false;

View File

@@ -27,12 +27,12 @@
#include <optional>
#include <span>
#include <wpi/util/SmallVector.hpp>
#include <wpi/apriltag/AprilTagFieldLayout.hpp>
#include <wpi/math/geometry/Pose3d.hpp>
#include <wpi/math/geometry/Rotation3d.hpp>
#include <wpi/math/geometry/Transform3d.hpp>
#include <wpi/math/interpolation/TimeInterpolatableBuffer.hpp>
#include <wpi/util/SmallVector.hpp>
#include "photon/PhotonCamera.h"
#include "photon/targeting/PhotonPipelineResult.h"
@@ -94,7 +94,7 @@ class PhotonPoseEstimator {
* @param robotToCamera Transform3d from the center of the robot to the camera
* mount positions (ie, robot ➔ camera).
*/
explicit PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags,
explicit PhotonPoseEstimator(wpi::apriltag::AprilTagFieldLayout aprilTags,
wpi::math::Transform3d robotToCamera);
/**
@@ -212,9 +212,7 @@ class PhotonPoseEstimator {
*/
[[deprecated("Use individual estimation methods instead.")]]
inline void SetLastPose(wpi::math::Pose3d lastPose) {
this->lastPose = lastPose;
}
/**
@@ -417,8 +415,8 @@ class PhotonPoseEstimator {
std::optional<EstimatedRobotPose> EstimateConstrainedSolvepnpPose(
photon::PhotonPipelineResult cameraResult,
photon::PhotonCamera::CameraMatrix cameraMatrix,
photon::PhotonCamera::DistortionMatrix distCoeffs, wpi::math::Pose3d seedPose,
bool headingFree, double headingScaleFactor);
photon::PhotonCamera::DistortionMatrix distCoeffs,
wpi::math::Pose3d seedPose, bool headingFree, double headingScaleFactor);
private:
wpi::apriltag::AprilTagFieldLayout aprilTags;

View File

@@ -50,10 +50,9 @@ class PhotonUtils {
* values up.
* @return The estimated distance to the target.
*/
static wpi::units::meter_t CalculateDistanceToTarget(wpi::units::meter_t cameraHeight,
wpi::units::meter_t targetHeight,
wpi::units::radian_t cameraPitch,
wpi::units::radian_t targetPitch) {
static wpi::units::meter_t CalculateDistanceToTarget(
wpi::units::meter_t cameraHeight, wpi::units::meter_t targetHeight,
wpi::units::radian_t cameraPitch, wpi::units::radian_t targetPitch) {
return (targetHeight - cameraHeight) /
wpi::units::math::tan(cameraPitch + targetPitch);
}

View File

@@ -88,7 +88,8 @@ class PhotonCameraSim {
* separate from this.
*/
PhotonCameraSim(PhotonCamera* camera, const SimCameraProperties& props,
double minTargetAreaPercent, wpi::units::meter_t maxSightRange);
double minTargetAreaPercent,
wpi::units::meter_t maxSightRange);
/**
* Returns the camera being simulated.
@@ -183,7 +184,9 @@ class PhotonCameraSim {
*
* @param rangeMeters The distance
*/
inline void SetMaxSightRange(wpi::units::meter_t range) { maxSightRange = range; }
inline void SetMaxSightRange(wpi::units::meter_t range) {
maxSightRange = range;
}
/**
* Sets whether the raw video stream simulation is enabled.
@@ -242,7 +245,7 @@ class PhotonCameraSim {
NTTopicSet ts{};
int64_t heartbeatCounter{0};
uint64_t nextNTEntryTime{wpi::util::Now()};
int64_t nextNTEntryTime{wpi::nt::Now()};
wpi::units::meter_t maxSightRange{std::numeric_limits<double>::max()};
static constexpr double kDefaultMinAreaPx{100};

View File

@@ -290,8 +290,8 @@ class SimCameraProperties {
}
wpi::math::Rotation2d GetDiagFOV() const {
return wpi::math::Rotation2d{
wpi::units::math::hypot(GetHorizFOV().Radians(), GetVertFOV().Radians())};
return wpi::math::Rotation2d{wpi::units::math::hypot(
GetHorizFOV().Radians(), GetVertFOV().Radians())};
}
/**
@@ -353,8 +353,8 @@ class SimCameraProperties {
* @return The latency estimate
*/
wpi::units::second_t EstLatency() {
return wpi::units::math::max(avgLatency + gaussian(generator) * latencyStdDev,
0_s);
return wpi::units::math::max(
avgLatency + gaussian(generator) * latencyStdDev, 0_s);
}
/**

View File

@@ -35,7 +35,7 @@
#include <opencv2/imgcodecs.hpp>
#include <opencv2/objdetect.hpp>
#include <wpi/apriltag/AprilTag.hpp>
#include <wpi/cs/cscore_cv.hpp>
#include <wpi/cs/CvSource.hpp>
#include <wpi/units/length.hpp>
#include "photon/simulation/SimCameraProperties.h"

View File

@@ -102,7 +102,7 @@ public class OpenCVTest {
var rvec = OpenCVHelp.rotationToRvec(rot);
var result = OpenCVHelp.rvecToRotation(rvec);
rvec.release();
var diff = result.minus(rot);
var diff = result.relativeTo(rot);
assertSame(new Rotation3d(), diff);
}

View File

@@ -34,6 +34,7 @@ import static org.photonvision.UnitTestUtils.waitForSequenceNumber;
import java.io.IOException;
import java.util.Arrays;
import java.util.List;
import java.util.Objects;
import java.util.Optional;
import java.util.stream.Stream;
import org.junit.jupiter.api.AfterEach;
@@ -56,6 +57,7 @@ import org.wpilib.hardware.hal.HAL;
import org.wpilib.math.geometry.Rotation2d;
import org.wpilib.networktables.NetworkTableInstance;
import org.wpilib.networktables.NetworkTablesJNI;
import org.wpilib.simulation.AlertSim;
import org.wpilib.simulation.SimHooks;
import org.wpilib.smartdashboard.SmartDashboard;
import org.wpilib.system.DataLogManager;
@@ -322,13 +324,16 @@ class PhotonCameraTest {
// WHEN we update the camera
camera.getAllUnreadResults();
// AND we tick SmartDashboard
SmartDashboard.updateValues();
// TODO: change to getActive once that exists
String[] alertsText =
Arrays.stream(AlertSim.getAll())
.filter(it -> it.isActive())
.map(it -> it.text)
.toArray(String[]::new);
// The alert state will be set (hard-coded here)
assertTrue(
Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0]))
.anyMatch(it -> it.equals(disconnectedCameraString)));
Arrays.stream(alertsText).anyMatch(it -> Objects.equals(it, disconnectedCameraString)));
Thread.sleep(20);
}
@@ -351,16 +356,18 @@ class PhotonCameraTest {
// WHEN we update the camera
camera.getAllUnreadResults();
// AND we tick SmartDashboard
SmartDashboard.updateValues();
// TODO: change to getActive once that exists
String[] alertsText =
Arrays.stream(AlertSim.getAll())
.filter(it -> it.isActive())
.map(it -> it.text)
.toArray(String[]::new);
// THEN the camera isn't disconnected
assertTrue(
Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0]))
.noneMatch(it -> it.equals(disconnectedCameraString)));
assertTrue(Arrays.stream(alertsText).noneMatch(it -> it.equals(disconnectedCameraString)));
// AND the alert string looks like a timesync warning
assertTrue(
Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0]))
Arrays.stream(alertsText)
.filter(it -> it.contains("is not connected to the TimeSyncServer"))
.count()
== 1);

View File

@@ -49,13 +49,11 @@ import org.photonvision.targeting.PhotonTrackedTarget;
import org.photonvision.targeting.PnpResult;
import org.photonvision.targeting.TargetCorner;
import org.wpilib.hardware.hal.HAL;
import org.wpilib.math.geometry.Pose2d;
import org.wpilib.math.geometry.Pose3d;
import org.wpilib.math.geometry.Quaternion;
import org.wpilib.math.geometry.Rotation2d;
import org.wpilib.math.geometry.Rotation3d;
import org.wpilib.math.geometry.Transform3d;
import org.wpilib.math.geometry.Translation2d;
import org.wpilib.math.geometry.Translation3d;
import org.wpilib.math.linalg.MatBuilder;
import org.wpilib.math.linalg.VecBuilder;

View File

@@ -26,14 +26,14 @@
#include <utility>
#include <vector>
#include <frc/apriltag/AprilTagFieldLayout.h>
#include <frc/geometry/Pose3d.h>
#include <frc/geometry/Rotation3d.h>
#include <frc/geometry/Transform3d.h>
#include <units/angle.h>
#include <units/length.h>
#include <wpi/SmallVector.h>
#include <wpi/deprecated.h>
#include <wpi/apriltag/AprilTagFieldLayout.hpp>
#include <wpi/math/geometry/Pose3d.hpp>
#include <wpi/math/geometry/Rotation3d.hpp>
#include <wpi/math/geometry/Transform3d.hpp>
#include <wpi/units/angle.hpp>
#include <wpi/units/length.hpp>
#include <wpi/util/SmallVector.hpp>
#include <wpi/util/deprecated.hpp>
#include "gtest/gtest.h"
#include "photon/PhotonCamera.h"
@@ -48,11 +48,13 @@
#include "photon/targeting/PnpResult.h"
WPI_IGNORE_DEPRECATED
namespace units = wpi::units;
static std::vector<wpi::apriltag::AprilTag> tags = {
{0, wpi::math::Pose3d(units::meter_t(3), units::meter_t(3), units::meter_t(3),
wpi::math::Rotation3d())},
{1, wpi::math::Pose3d(units::meter_t(5), units::meter_t(5), units::meter_t(5),
wpi::math::Rotation3d())}};
{0, wpi::math::Pose3d(units::meter_t(3), units::meter_t(3),
units::meter_t(3), wpi::math::Rotation3d())},
{1, wpi::math::Pose3d(units::meter_t(5), units::meter_t(5),
units::meter_t(5), wpi::math::Rotation3d())}};
static wpi::apriltag::AprilTagFieldLayout aprilTags{tags, 54_ft, 27_ft};
@@ -70,23 +72,23 @@ TEST(LegacyPhotonPoseEstimatorTest, LowestAmbiguityStrategy) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 2_m, 3_m),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 2_m, 3_m),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(4_m, 2_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(4_m, 2_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners},
photon::PhotonTrackedTarget{
9.0, -2.0, 19.0, 3.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 2_m, 3_m),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 2_m, 3_m),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
0.4, corners, detectedCorners}};
cameraOne.test = true;
@@ -113,10 +115,10 @@ TEST(LegacyPhotonPoseEstimatorTest, LowestAmbiguityStrategy) {
TEST(LegacyPhotonPoseEstimatorTest, ClosestToCameraHeightStrategy) {
std::vector<wpi::apriltag::AprilTag> tags = {
{0, wpi::math::Pose3d(units::meter_t(3), units::meter_t(3), units::meter_t(3),
wpi::math::Rotation3d())},
{1, wpi::math::Pose3d(units::meter_t(5), units::meter_t(5), units::meter_t(5),
wpi::math::Rotation3d())},
{0, wpi::math::Pose3d(units::meter_t(3), units::meter_t(3),
units::meter_t(3), wpi::math::Rotation3d())},
{1, wpi::math::Pose3d(units::meter_t(5), units::meter_t(5),
units::meter_t(5), wpi::math::Rotation3d())},
};
auto aprilTags = wpi::apriltag::AprilTagFieldLayout(tags, 54_ft, 27_ft);
@@ -131,23 +133,23 @@ TEST(LegacyPhotonPoseEstimatorTest, ClosestToCameraHeightStrategy) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(0_m, 0_m, 0_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 1_m, 1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 2_m, 2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners},
photon::PhotonTrackedTarget{
9.0, -2.0, 19.0, 3.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(4_m, 4_m, 4_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(5_m, 5_m, 5_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.4, corners, detectedCorners}};
cameraOne.test = true;
@@ -180,23 +182,23 @@ TEST(LegacyPhotonPoseEstimatorTest, ClosestToReferencePoseStrategy) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(0_m, 0_m, 0_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 1_m, 1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 2_m, 2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners},
photon::PhotonTrackedTarget{
9.0, -2.0, 19.0, 3.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2.2_m, 2.2_m, 2.2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 1.9_m, 2.1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.4, corners, detectedCorners}};
cameraOne.test = true;
@@ -206,8 +208,8 @@ TEST(LegacyPhotonPoseEstimatorTest, ClosestToReferencePoseStrategy) {
photon::PhotonPoseEstimator estimator(aprilTags,
photon::CLOSEST_TO_REFERENCE_POSE, {});
estimator.SetReferencePose(
wpi::math::Pose3d(1_m, 1_m, 1_m, wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)));
estimator.SetReferencePose(wpi::math::Pose3d(
1_m, 1_m, 1_m, wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)));
std::optional<photon::EstimatedRobotPose> estimatedPose;
for (const auto& result : cameraOne.GetAllUnreadResults()) {
@@ -231,23 +233,23 @@ TEST(LegacyPhotonPoseEstimatorTest, ClosestToLastPose) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(0_m, 0_m, 0_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 1_m, 1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 2_m, 2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners},
photon::PhotonTrackedTarget{
9.0, -2.0, 19.0, 3.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2.2_m, 2.2_m, 2.2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 1.9_m, 2.1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.4, corners, detectedCorners}};
cameraOne.test = true;
@@ -257,8 +259,8 @@ TEST(LegacyPhotonPoseEstimatorTest, ClosestToLastPose) {
photon::PhotonPoseEstimator estimator(aprilTags, photon::CLOSEST_TO_LAST_POSE,
{});
estimator.SetLastPose(
wpi::math::Pose3d(1_m, 1_m, 1_m, wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)));
estimator.SetLastPose(wpi::math::Pose3d(
1_m, 1_m, 1_m, wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)));
std::optional<photon::EstimatedRobotPose> estimatedPose;
for (const auto& result : cameraOne.GetAllUnreadResults()) {
@@ -272,23 +274,23 @@ TEST(LegacyPhotonPoseEstimatorTest, ClosestToLastPose) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(0_m, 0_m, 0_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 1_m, 1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2.1_m, 1.9_m, 2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners},
photon::PhotonTrackedTarget{
9.0, -2.0, 19.0, 3.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2.4_m, 2.4_m, 2.2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 1_m, 2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.4, corners, detectedCorners}};
cameraOne.testResult = {photon::PhotonPipelineResult{
@@ -332,8 +334,8 @@ TEST(LegacyPhotonPoseEstimatorTest, PnpDistanceTrigSolve) {
aprilTags, photon::PNP_DISTANCE_TRIG_SOLVE, compoundTestTransform);
/* real pose of the robot base to test against */
wpi::math::Pose3d realPose =
wpi::math::Pose3d(7.3_m, 4.42_m, 0_m, wpi::math::Rotation3d(0_rad, 0_rad, 2.197_rad));
wpi::math::Pose3d realPose = wpi::math::Pose3d(
7.3_m, 4.42_m, 0_m, wpi::math::Rotation3d(0_rad, 0_rad, 2.197_rad));
photon::PhotonPipelineResult result = cameraOneSim.Process(
1_ms, realPose.TransformBy(estimator.GetRobotToCameraTransform()),
@@ -359,12 +361,12 @@ TEST(LegacyPhotonPoseEstimatorTest, PnpDistanceTrigSolve) {
units::unit_cast<double>(pose.Z()), .01);
/* Straight on */
wpi::math::Transform3d straightOnTestTransform =
wpi::math::Transform3d(0_m, 0_m, 3_m, wpi::math::Rotation3d(0_rad, 0_rad, 0_rad));
wpi::math::Transform3d straightOnTestTransform = wpi::math::Transform3d(
0_m, 0_m, 3_m, wpi::math::Rotation3d(0_rad, 0_rad, 0_rad));
estimator.SetRobotToCameraTransform(straightOnTestTransform);
realPose = wpi::math::Pose3d(4.81_m, 2.38_m, 0_m,
wpi::math::Rotation3d(0_rad, 0_rad, 2.818_rad));
wpi::math::Rotation3d(0_rad, 0_rad, 2.818_rad));
result = cameraOneSim.Process(
1_ms, realPose.TransformBy(estimator.GetRobotToCameraTransform()),
targets);
@@ -396,23 +398,23 @@ TEST(LegacyPhotonPoseEstimatorTest, AverageBestPoses) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 2_m, 2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 1_m, 1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners},
photon::PhotonTrackedTarget{
9.0, -2.0, 19.0, 3.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(0_m, 0_m, 0_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 1.9_m, 2.1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.4, corners, detectedCorners}};
cameraOne.test = true;
@@ -445,23 +447,23 @@ TEST(LegacyPhotonPoseEstimatorTest, PoseCache) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 2_m, 2_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 1_m, 1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(3_m, 3_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners},
photon::PhotonTrackedTarget{
9.0, -2.0, 19.0, 3.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(0_m, 0_m, 0_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(2_m, 1.9_m, 2.1_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.4, corners, detectedCorners}};
cameraOne.test = true;
@@ -520,8 +522,9 @@ TEST(LegacyPhotonPoseEstimatorTest, PoseCache) {
EXPECT_FALSE(estimatedPose);
// Setting ReferencePose should also clear the cache
estimator.SetReferencePose(wpi::math::Pose3d(units::meter_t(1), units::meter_t(2),
units::meter_t(3), wpi::math::Rotation3d()));
estimator.SetReferencePose(
wpi::math::Pose3d(units::meter_t(1), units::meter_t(2), units::meter_t(3),
wpi::math::Rotation3d()));
for (const auto& result : cameraOne.GetAllUnreadResults()) {
estimatedPose = estimator.Update(result);
@@ -539,16 +542,16 @@ TEST(LegacyPhotonPoseEstimatorTest, MultiTagOnRioFallback) {
photon::PhotonTrackedTarget{
3.0, -4.0, 9.0, 4.0, 0, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 2_m, 3_m),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(1_m, 2_m, 3_m),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
wpi::math::Rotation3d(1_rad, 2_rad, 3_rad)),
0.7, corners, detectedCorners},
photon::PhotonTrackedTarget{
3.0, -4.0, 9.1, 6.7, 1, -1, -1.f,
wpi::math::Transform3d(wpi::math::Translation3d(4_m, 2_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Transform3d(wpi::math::Translation3d(4_m, 2_m, 3_m),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)),
0.3, corners, detectedCorners}};
cameraOne.test = true;
@@ -589,7 +592,8 @@ TEST(LegacyPhotonPoseEstimatorTest, CopyResult) {
TEST(LegacyPhotonPoseEstimatorTest, ConstrainedPnpEmptyCase) {
photon::PhotonPoseEstimator estimator(
wpi::apriltag::AprilTagFieldLayout::LoadField(wpi::apriltag::AprilTagField::k2024Crescendo),
wpi::apriltag::AprilTagFieldLayout::LoadField(
wpi::apriltag::AprilTagField::k2024Crescendo),
photon::CONSTRAINED_SOLVEPNP, wpi::math::Transform3d());
photon::PhotonPipelineResult result;
@@ -613,10 +617,10 @@ TEST(LegacyPhotonPoseEstimatorTest, ConstrainedPnpOneTag) {
wpi::math::Transform3d poseTransform(
wpi::math::Translation3d(3.1665557336121353_m, 4.430673446050584_m,
0.48678786477534686_m),
wpi::math::Rotation3d(wpi::math::Quaternion(0.3132532247418243, 0.24722671090692333,
-0.08413452932300695,
0.9130568172784148)));
0.48678786477534686_m),
wpi::math::Rotation3d(
wpi::math::Quaternion(0.3132532247418243, 0.24722671090692333,
-0.08413452932300695, 0.9130568172784148)));
std::vector<photon::PhotonTrackedTarget> targets{
photon::PhotonTrackedTarget{0.0, 0.0, 0.0, 0.0, 8, 0, 0.0f, poseTransform,
@@ -635,11 +639,13 @@ TEST(LegacyPhotonPoseEstimatorTest, ConstrainedPnpOneTag) {
cameraOne.testResult[0].SetReceiveTimestamp(units::second_t(15));
const units::radian_t camPitch = 30_deg;
const wpi::math::Transform3d kRobotToCam{wpi::math::Translation3d(0.5_m, 0.0_m, 0.5_m),
wpi::math::Rotation3d(0_rad, -camPitch, 0_rad)};
const wpi::math::Transform3d kRobotToCam{
wpi::math::Translation3d(0.5_m, 0.0_m, 0.5_m),
wpi::math::Rotation3d(0_rad, -camPitch, 0_rad)};
photon::PhotonPoseEstimator estimator(
wpi::apriltag::AprilTagFieldLayout::LoadField(wpi::apriltag::AprilTagField::k2024Crescendo),
wpi::apriltag::AprilTagFieldLayout::LoadField(
wpi::apriltag::AprilTagField::k2024Crescendo),
photon::CONSTRAINED_SOLVEPNP, kRobotToCam);
estimator.AddHeadingData(cameraOne.testResult[0].GetTimestamp(),

View File

@@ -33,6 +33,7 @@
#include <photon/simulation/PhotonCameraSim.h>
#include <wpi/hal/HAL.h>
#include <wpi/nt/NetworkTableInstance.hpp>
#include <wpi/simulation/AlertSim.hpp>
#include <wpi/smartdashboard/SmartDashboard.hpp>
TEST(TimeSyncProtocolTest, Smoketest) {
@@ -60,8 +61,6 @@ TEST(TimeSyncProtocolTest, Smoketest) {
}
TEST(PhotonCameraTest, Alerts) {
using wpi::SmartDashboard;
// GIVEN a local-only NT instance
auto inst = wpi::nt::NetworkTableInstance::GetDefault();
inst.StopClient();
@@ -78,20 +77,29 @@ TEST(PhotonCameraTest, Alerts) {
std::string disconnectedCameraString =
"PhotonCamera '" + cameraName + "' is disconnected.";
// TODO: Replace this when getActive is upstreamed to wpilib
auto getActiveAlerts = []() {
auto infos = wpi::sim::AlertSim::GetAll();
std::erase_if(infos, [](const wpi::sim::AlertSim::AlertInfo& info) {
return !info.isActive();
});
return infos;
};
// Loop to hit cases past first iteration
for (int i = 0; i < 10; i++) {
// WHEN we update the camera
camera.GetAllUnreadResults();
// AND we tick SmartDashboard
SmartDashboard::UpdateValues();
// The alert state will be set (hard-coded here)
auto alerts = SmartDashboard::GetStringArray("PhotonAlerts/warnings", {});
EXPECT_TRUE(
std::any_of(alerts.begin(), alerts.end(),
[&disconnectedCameraString](const std::string& alert) {
return alert == disconnectedCameraString;
}));
auto alerts = getActiveAlerts();
EXPECT_TRUE(std::any_of(alerts.begin(), alerts.end(),
[&disconnectedCameraString](
const wpi::sim::AlertSim::AlertInfo& alert) {
return alert.text == disconnectedCameraString;
}));
std::this_thread::sleep_for(std::chrono::milliseconds(20));
}
@@ -109,25 +117,23 @@ TEST(PhotonCameraTest, Alerts) {
sim.SubmitProcessedFrame(noPongResult);
// WHEN we update the camera
camera.GetAllUnreadResults();
// AND we tick SmartDashboard
SmartDashboard::UpdateValues();
// THEN the camera isn't disconnected
auto alerts = SmartDashboard::GetStringArray("PhotonAlerts/warnings", {});
fmt::println("{}:{}: saw alerts: {}", __FILE__, __LINE__, alerts);
EXPECT_TRUE(
std::none_of(alerts.begin(), alerts.end(),
[&disconnectedCameraString](const std::string& alert) {
return alert == disconnectedCameraString;
}));
auto alerts = getActiveAlerts();
EXPECT_TRUE(std::none_of(alerts.begin(), alerts.end(),
[&disconnectedCameraString](
const wpi::sim::AlertSim::AlertInfo& alert) {
return alert.text == disconnectedCameraString;
}));
// AND the alert string looks like a timesync warning
EXPECT_EQ(
1, std::count_if(
alerts.begin(), alerts.end(), [](const std::string& alert) {
return alert.find("is not connected to the TimeSyncServer") !=
std::string::npos;
}));
EXPECT_EQ(1, std::count_if(
alerts.begin(), alerts.end(),
[](const wpi::sim::AlertSim::AlertInfo& alert) {
return alert.text.find(
"is not connected to the TimeSyncServer") !=
std::string::npos;
}));
std::this_thread::sleep_for(std::chrono::milliseconds(20));
}

View File

@@ -205,8 +205,8 @@ TEST(PhotonPoseEstimatorTest, ClosestToReferencePoseStrategy) {
std::optional<photon::EstimatedRobotPose> estimatedPose;
for (const auto& result : cameraOne.GetAllUnreadResults()) {
estimatedPose = estimator.EstimateClosestToReferencePose(
result,
wpi::math::Pose3d(1_m, 1_m, 1_m, wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)));
result, wpi::math::Pose3d(1_m, 1_m, 1_m,
wpi::math::Rotation3d(0_rad, 0_rad, 0_rad)));
}
ASSERT_TRUE(estimatedPose);
@@ -493,10 +493,15 @@ TEST(PhotonPoseEstimatorTest, ConstrainedPnpEmptyCase) {
photon::PhotonPoseEstimator estimator(
wpi::apriltag::AprilTagFieldLayout::LoadField(
wpi::apriltag::AprilTagField::k2024Crescendo),
photon::CONSTRAINED_SOLVEPNP, wpi::math::Transform3d());
wpi::math::Transform3d());
photon::PhotonPipelineResult result;
auto estimate = estimator.Update(result);
auto distortion = Eigen::VectorXd::Zero(8);
auto cameraMat = Eigen::Matrix3d{{399.37500000000006, 0, 319.5},
{0, 399.16666666666674, 239.5},
{0, 0, 1}};
auto estimate = estimator.EstimateConstrainedSolvepnpPose(
result, cameraMat, distortion, wpi::math::Pose3d(), true, 0.0);
EXPECT_FALSE(estimate.has_value());
}

View File

@@ -23,10 +23,10 @@
*/
#include <gtest/gtest.h>
#include <wpi/print.h>
#include <wpi/util/print.hpp>
#include "PhotonVersion.h"
TEST(VersionTest, PrintVersion) {
wpi::println("{}", photon::PhotonVersion::versionString);
wpi::util::println("{}", photon::PhotonVersion::versionString);
}

View File

@@ -50,13 +50,14 @@ class VisionSystemSimTestWithParamsTest
public testing::WithParamInterface<wpi::units::degree_t> {};
class VisionSystemSimTestDistanceParamsTest
: public VisionSystemSimTest,
public testing::WithParamInterface<
std::tuple<wpi::units::foot_t, wpi::units::degree_t, wpi::units::foot_t>> {};
public testing::WithParamInterface<std::tuple<
wpi::units::foot_t, wpi::units::degree_t, wpi::units::foot_t>> {};
TEST_F(VisionSystemSimTest, TestVisibilityCupidShuffle) {
wpi::math::Pose3d targetPose{
wpi::math::Translation3d{15.98_m, 0_m, 2_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
photon::VisionSystemSim visionSysSim{"Test"};
photon::PhotonCamera camera{"camera"};
@@ -110,10 +111,11 @@ TEST_F(VisionSystemSimTest, TestVisibilityCupidShuffle) {
// Now walk it by yourself
visionSysSim.AdjustCamera(
&cameraSim, wpi::math::Transform3d{
wpi::math::Translation3d{},
wpi::math::Rotation3d{
0_deg, 0_deg, wpi::units::radian_t{std::numbers::pi}}});
&cameraSim,
wpi::math::Transform3d{
wpi::math::Translation3d{},
wpi::math::Rotation3d{0_deg, 0_deg,
wpi::units::radian_t{std::numbers::pi}}});
visionSysSim.Update(robotPose);
ASSERT_TRUE(camera.GetLatestResult().HasTargets());
}
@@ -122,20 +124,22 @@ TEST_F(VisionSystemSimTest, TestBunchaTargets) {
photon::VisionSystemSim visionSysSim{"Test"};
photon::PhotonCamera camera{"camera"};
photon::PhotonCameraSim cameraSim{&camera};
visionSysSim.AddCamera(&cameraSim, frc::Transform3d{});
cameraSim.prop.SetCalibration(640, 480, frc::Rotation2d{80_deg});
visionSysSim.AddCamera(&cameraSim, wpi::math::Transform3d{});
cameraSim.prop.SetCalibration(640, 480, wpi::math::Rotation2d{80_deg});
std::vector<photon::VisionTargetSim> targets;
for (int i = 0; i < 100; i++) {
targets.emplace_back(
frc::Pose3d{
frc::Translation3d{15.98_m + i * 0.1_m, 0_m, 1_m},
frc::Rotation3d{0_rad, 0_rad, units::radian_t{std::numbers::pi}}},
wpi::math::Pose3d{
wpi::math::Translation3d{15.98_m + i * 0.1_m, 0_m, 1_m},
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}},
photon::TargetModel{0.5_m, 0.5_m}, i);
}
visionSysSim.AddVisionTargets(targets);
frc::Pose2d robotPose{frc::Translation2d{5_m, 0_m}, frc::Rotation2d{5_deg}};
wpi::math::Pose2d robotPose{wpi::math::Translation2d{5_m, 0_m},
wpi::math::Rotation2d{5_deg}};
visionSysSim.Update(robotPose);
ASSERT_EQ(camera.GetLatestResult().targets.size(), 50u);
@@ -144,7 +148,8 @@ TEST_F(VisionSystemSimTest, TestBunchaTargets) {
TEST_F(VisionSystemSimTest, TestNotVisibleVert1) {
wpi::math::Pose3d targetPose{
wpi::math::Translation3d{15.98_m, 0_m, 1_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
photon::VisionSystemSim visionSysSim{"Test"};
photon::PhotonCamera camera{"camera"};
@@ -160,10 +165,11 @@ TEST_F(VisionSystemSimTest, TestNotVisibleVert1) {
ASSERT_TRUE(camera.GetLatestResult().HasTargets());
visionSysSim.AdjustCamera(
&cameraSim, wpi::math::Transform3d{
wpi::math::Translation3d{0_m, 0_m, 5000_m},
wpi::math::Rotation3d{
0_deg, 0_deg, wpi::units::radian_t{std::numbers::pi}}});
&cameraSim,
wpi::math::Transform3d{
wpi::math::Translation3d{0_m, 0_m, 5000_m},
wpi::math::Rotation3d{0_deg, 0_deg,
wpi::units::radian_t{std::numbers::pi}}});
visionSysSim.Update(robotPose);
ASSERT_FALSE(camera.GetLatestResult().HasTargets());
}
@@ -171,7 +177,8 @@ TEST_F(VisionSystemSimTest, TestNotVisibleVert1) {
TEST_F(VisionSystemSimTest, TestNotVisibleVert2) {
wpi::math::Pose3d targetPose{
wpi::math::Translation3d{15.98_m, 0_m, 2_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Transform3d robotToCamera{
wpi::math::Translation3d{0_m, 0_m, 1_m},
@@ -200,7 +207,8 @@ TEST_F(VisionSystemSimTest, TestNotVisibleVert2) {
TEST_F(VisionSystemSimTest, TestNotVisibleTargetSize) {
wpi::math::Pose3d targetPose{
wpi::math::Translation3d{15.98_m, 0_m, 1_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
photon::VisionSystemSim visionSysSim{"Test"};
photon::PhotonCamera camera{"camera"};
@@ -225,7 +233,8 @@ TEST_F(VisionSystemSimTest, TestNotVisibleTargetSize) {
TEST_F(VisionSystemSimTest, TestNotVisibleTooFarLeds) {
wpi::math::Pose3d targetPose{
wpi::math::Translation3d{15.98_m, 0_m, 1_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
photon::VisionSystemSim visionSysSim{"Test"};
photon::PhotonCamera camera{"camera"};
@@ -291,10 +300,10 @@ TEST_P(VisionSystemSimTestWithParamsTest, PitchAngles) {
robotPose = wpi::math::Pose2d{wpi::math::Translation2d{10_m, 0_m},
wpi::math::Rotation2d{-1 * GetParam()}};
visionSysSim.AdjustCamera(
&cameraSim,
wpi::math::Transform3d{
wpi::math::Translation3d{},
wpi::math::Rotation3d{0_rad, wpi::units::degree_t{GetParam()}, 0_rad}});
&cameraSim, wpi::math::Transform3d{
wpi::math::Translation3d{},
wpi::math::Rotation3d{
0_rad, wpi::units::degree_t{GetParam()}, 0_rad}});
visionSysSim.Update(robotPose);
const auto result = camera.GetLatestResult();
@@ -370,13 +379,16 @@ INSTANTIATE_TEST_SUITE_P(
TEST_F(VisionSystemSimTest, TestMultipleTargets) {
wpi::math::Pose3d targetPoseL{
wpi::math::Translation3d{15.98_m, 2_m, 0_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Pose3d targetPoseC{
wpi::math::Translation3d{15.98_m, 0_m, 0_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Pose3d targetPoseR{
wpi::math::Translation3d{15.98_m, -2_m, 0_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
photon::VisionSystemSim visionSysSim{"Test"};
photon::PhotonCamera camera{"camera"};
@@ -449,20 +461,20 @@ TEST_F(VisionSystemSimTest, TestPoseEstimation) {
std::vector<wpi::apriltag::AprilTag> tagList;
tagList.emplace_back(wpi::apriltag::AprilTag{
0,
wpi::math::Pose3d{12_m, 3_m, 1_m,
wpi::math::Rotation3d{
0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}}});
0, wpi::math::Pose3d{
12_m, 3_m, 1_m,
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}}});
tagList.emplace_back(wpi::apriltag::AprilTag{
1,
wpi::math::Pose3d{12_m, 1_m, -1_m,
wpi::math::Rotation3d{
0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}}});
1, wpi::math::Pose3d{
12_m, 1_m, -1_m,
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}}});
tagList.emplace_back(wpi::apriltag::AprilTag{
2,
wpi::math::Pose3d{11_m, 0_m, 2_m,
wpi::math::Rotation3d{
0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}}});
2, wpi::math::Pose3d{
11_m, 0_m, 2_m,
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}}});
wpi::units::meter_t fieldLength{54};
wpi::units::meter_t fieldWidth{27};
wpi::apriltag::AprilTagFieldLayout layout{tagList, fieldLength, fieldWidth};
@@ -488,8 +500,9 @@ TEST_F(VisionSystemSimTest, TestPoseEstimation) {
ASSERT_NEAR(5, pose.X().to<double>(), 0.01);
ASSERT_NEAR(1, pose.Y().to<double>(), 0.01);
ASSERT_NEAR(0, pose.Z().to<double>(), 0.01);
ASSERT_NEAR(wpi::units::degree_t{5}.convert<wpi::units::radians>().to<double>(),
pose.Rotation().Z().to<double>(), 0.01);
ASSERT_NEAR(
wpi::units::degree_t{5}.convert<wpi::units::radians>().to<double>(),
pose.Rotation().Z().to<double>(), 0.01);
visionSysSim.AddVisionTargets(
{photon::VisionTargetSim{tagList[1].pose, photon::kAprilTag16h5, 1}});
@@ -510,8 +523,9 @@ TEST_F(VisionSystemSimTest, TestPoseEstimation) {
ASSERT_NEAR(robotPose.X().to<double>(), pose2.X().to<double>(), 0.01);
ASSERT_NEAR(robotPose.Y().to<double>(), pose2.Y().to<double>(), 0.01);
ASSERT_NEAR(0, pose2.Z().to<double>(), 0.01);
ASSERT_NEAR(wpi::units::degree_t{5}.convert<wpi::units::radians>().to<double>(),
pose2.Rotation().Z().to<double>(), 0.01);
ASSERT_NEAR(
wpi::units::degree_t{5}.convert<wpi::units::radians>().to<double>(),
pose2.Rotation().Z().to<double>(), 0.01);
}
TEST_F(VisionSystemSimTest, TestPoseEstimationRotated) {
@@ -528,20 +542,20 @@ TEST_F(VisionSystemSimTest, TestPoseEstimationRotated) {
std::vector<wpi::apriltag::AprilTag> tagList;
tagList.emplace_back(wpi::apriltag::AprilTag{
0,
wpi::math::Pose3d{12_m, 3_m, 1_m,
wpi::math::Rotation3d{
0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}}});
0, wpi::math::Pose3d{
12_m, 3_m, 1_m,
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}}});
tagList.emplace_back(wpi::apriltag::AprilTag{
1,
wpi::math::Pose3d{12_m, 1_m, -1_m,
wpi::math::Rotation3d{
0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}}});
1, wpi::math::Pose3d{
12_m, 1_m, -1_m,
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}}});
tagList.emplace_back(wpi::apriltag::AprilTag{
2,
wpi::math::Pose3d{11_m, 0_m, 2_m,
wpi::math::Rotation3d{
0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}}});
2, wpi::math::Pose3d{
11_m, 0_m, 2_m,
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}}});
wpi::units::meter_t fieldLength{54};
wpi::units::meter_t fieldWidth{27};
wpi::apriltag::AprilTagFieldLayout layout{tagList, fieldLength, fieldWidth};
@@ -572,8 +586,9 @@ TEST_F(VisionSystemSimTest, TestPoseEstimationRotated) {
ASSERT_NEAR(5, pose.X().to<double>(), 0.01);
ASSERT_NEAR(1, pose.Y().to<double>(), 0.01);
ASSERT_NEAR(0, pose.Z().to<double>(), 0.01);
ASSERT_NEAR(wpi::units::degree_t{-5}.convert<wpi::units::radians>().to<double>(),
pose.Rotation().Z().to<double>(), 0.01);
ASSERT_NEAR(
wpi::units::degree_t{-5}.convert<wpi::units::radians>().to<double>(),
pose.Rotation().Z().to<double>(), 0.01);
visionSysSim.AddVisionTargets(
{photon::VisionTargetSim{tagList[1].pose, photon::kAprilTag36h11, 1}});
@@ -595,8 +610,9 @@ TEST_F(VisionSystemSimTest, TestPoseEstimationRotated) {
ASSERT_NEAR(robotPose.X().to<double>(), pose2.X().to<double>(), 0.01);
ASSERT_NEAR(robotPose.Y().to<double>(), pose2.Y().to<double>(), 0.01);
ASSERT_NEAR(0, pose2.Z().to<double>(), 0.01);
ASSERT_NEAR(wpi::units::degree_t{-5}.convert<wpi::units::radians>().to<double>(),
pose2.Rotation().Z().to<double>(), 0.01);
ASSERT_NEAR(
wpi::units::degree_t{-5}.convert<wpi::units::radians>().to<double>(),
pose2.Rotation().Z().to<double>(), 0.01);
}
TEST_F(VisionSystemSimTest, TestTagAmbiguity) {
@@ -609,7 +625,8 @@ TEST_F(VisionSystemSimTest, TestTagAmbiguity) {
wpi::math::Pose3d targetPose{
wpi::math::Translation3d{2_m, 0_m, 0_m},
wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi}}};
wpi::math::Rotation3d{0_rad, 0_rad,
wpi::units::radian_t{std::numbers::pi}}};
visionSysSim.AddVisionTargets(
{photon::VisionTargetSim{targetPose, photon::kAprilTag36h11, 3}});

View File

@@ -1,6 +1,11 @@
import org.wpilib.deployutils.deploy.artifact.*
import org.wpilib.deployutils.deploy.target.RemoteTarget
import org.wpilib.deployutils.deploy.target.location.SshDeployLocation
apply plugin: "com.github.node-gradle.node"
apply plugin: 'com.gradleup.shadow'
apply plugin: "application"
apply plugin: 'org.wpilib.DeployUtils'
apply from: "${rootDir}/shared/common.gradle"
@@ -75,9 +80,6 @@ run {
}
}
import org.wpilib.deployutils.deploy.artifact.*
import org.wpilib.deployutils.deploy.target.RemoteTarget
import org.wpilib.deployutils.deploy.target.location.SshDeployLocation
deploy {
targets {
pi(RemoteTarget) {

View File

@@ -55,6 +55,7 @@ import org.photonvision.vision.pipeline.PipelineProfiler;
import org.photonvision.vision.processes.VisionSourceManager;
import org.photonvision.vision.target.TargetModel;
import org.wpilib.hardware.hal.HAL;
import org.wpilib.math.geometry.Rotation2d;
public class Main {
public static final int DEFAULT_WEBPORT = 5800;
@@ -242,8 +243,6 @@ public class Main {
if (OsImageData.IMAGE_METADATA.isPresent()) {
logger.info("PhotonVision image data: " + OsImageData.IMAGE_METADATA.get());
} else if (OsImageData.IMAGE_VERSION.isPresent()) {
logger.info("PhotonVision image version: " + OsImageData.IMAGE_VERSION.get());
} else {
logger.info("PhotonVision image version: unknown");
}

View File

@@ -169,7 +169,7 @@ cppHeadersZip {
}
// setup wpilib bundled native libs
wpilibTools.deps.wpilibVersion = wpi.versions.wpilibVersion.get()
wpilibTools.deps.wpilibVersion = wpilibVersion
def nativeConfigName = 'wpilibNatives'
def nativeConfig = configurations.create(nativeConfigName)
@@ -187,5 +187,5 @@ nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpinet")
nativeConfig.dependencies.add wpilibTools.deps.wpilib("ntcore")
nativeConfig.dependencies.add wpilibTools.deps.wpilib("hal")
nativeConfig.dependencies.add wpilibTools.deps.wpilib("cscore")
nativeConfig.dependencies.add wpilibTools.deps.wpilibOpenCv("frc" + openCVYear, wpi.versions.opencvVersion.get())
nativeConfig.dependencies.add wpilibTools.deps.wpilibOpenCv("frc" + openCVYear, openCVversion)
nativeConfig.dependencies.add wpilibTools.deps.wpilib("apriltag")

View File

@@ -28,13 +28,12 @@ package org.photonvision.struct;
import org.photonvision.common.dataflow.structures.Packet;
import org.photonvision.common.dataflow.structures.PacketSerde;
import org.photonvision.utils.PacketUtils;
// Assume that the base class lives here and we can import it
import org.photonvision.targeting.*;
// WPILib imports (if any)
import edu.wpi.first.util.struct.Struct;
import org.wpilib.util.struct.Struct;
/**

View File

@@ -28,13 +28,12 @@ package org.photonvision.struct;
import org.photonvision.common.dataflow.structures.Packet;
import org.photonvision.common.dataflow.structures.PacketSerde;
import org.photonvision.utils.PacketUtils;
// Assume that the base class lives here and we can import it
import org.photonvision.targeting.*;
// WPILib imports (if any)
import edu.wpi.first.util.struct.Struct;
import org.wpilib.util.struct.Struct;
/**

View File

@@ -28,13 +28,12 @@ package org.photonvision.struct;
import org.photonvision.common.dataflow.structures.Packet;
import org.photonvision.common.dataflow.structures.PacketSerde;
import org.photonvision.utils.PacketUtils;
// Assume that the base class lives here and we can import it
import org.photonvision.targeting.*;
// WPILib imports (if any)
import edu.wpi.first.util.struct.Struct;
import org.wpilib.util.struct.Struct;
/**

View File

@@ -34,7 +34,7 @@ import org.photonvision.utils.PacketUtils;
import org.photonvision.targeting.*;
// WPILib imports (if any)
import edu.wpi.first.util.struct.Struct;
import org.wpilib.util.struct.Struct;
import org.wpilib.math.geometry.Transform3d;
/**

View File

@@ -34,7 +34,7 @@ import org.photonvision.utils.PacketUtils;
import org.photonvision.targeting.*;
// WPILib imports (if any)
import edu.wpi.first.util.struct.Struct;
import org.wpilib.util.struct.Struct;
import org.wpilib.math.geometry.Transform3d;
/**

View File

@@ -28,13 +28,12 @@ package org.photonvision.struct;
import org.photonvision.common.dataflow.structures.Packet;
import org.photonvision.common.dataflow.structures.PacketSerde;
import org.photonvision.utils.PacketUtils;
// Assume that the base class lives here and we can import it
import org.photonvision.targeting.*;
// WPILib imports (if any)
import edu.wpi.first.util.struct.Struct;
import org.wpilib.util.struct.Struct;
/**

View File

@@ -36,7 +36,7 @@
#include "photon/targeting/TargetCorner.h"
#include <stdint.h>
#include <vector>
#include <wpi/math/geometry/Transform3d.h>
#include <wpi/math/geometry/Transform3d.hpp>
namespace photon {

View File

@@ -34,7 +34,7 @@
// Includes for dependant types
#include <stdint.h>
#include <wpi/math/geometry/Transform3d.h>
#include <wpi/math/geometry/Transform3d.hpp>
namespace photon {

View File

@@ -30,7 +30,7 @@
#include "photon/targeting/TargetCorner.h"
#include <stdint.h>
#include <vector>
#include <wpi/math/geometry/Transform3d.h>
#include <wpi/math/geometry/Transform3d.hpp>
namespace photon {

View File

@@ -28,7 +28,7 @@
// Includes for dependant types
#include <stdint.h>
#include <wpi/math/geometry/Transform3d.h>
#include <wpi/math/geometry/Transform3d.hpp>
namespace photon {

View File

@@ -85,15 +85,15 @@ public class NTTopicSet {
.publish(
PhotonPipelineResult.photonStruct.getTypeString(),
PubSubOption.periodic(0.01),
PubSubOption.sendAll(true),
PubSubOption.keepDuplicates(true));
PubSubOption.SEND_ALL,
PubSubOption.KEEP_DUPLICATES);
resultPublisher =
new PacketPublisher<PhotonPipelineResult>(rawBytesEntry, PhotonPipelineResult.photonStruct);
protoResultPublisher =
subTable
.getProtobufTopic("result_proto", PhotonPipelineResult.proto)
.publish(PubSubOption.periodic(0.01), PubSubOption.sendAll(true));
.publish(PubSubOption.periodic(0.01), PubSubOption.SEND_ALL);
pipelineIndexPublisher = subTable.getIntegerTopic("pipelineIndexState").publish();
pipelineIndexRequestSub = subTable.getIntegerTopic("pipelineIndexRequest").subscribe(0);

View File

@@ -48,7 +48,6 @@ import org.wpilib.math.linalg.VecBuilder;
import org.wpilib.math.numbers.*;
import org.wpilib.math.util.Nat;
import org.wpilib.math.util.Num;
import org.wpilib.vision.camera.OpenCvLoader;
/**
* A set of various utility functions for getting non-OpenCV data into an OpenCV-compatible format,
@@ -269,7 +268,7 @@ public final class OpenCVHelp {
* @return The converted rotation in the NWU coordinate system
*/
private static Rotation3d rotationEDNtoNWU(Rotation3d rot) {
return EDN_TO_NWU.unaryMinus().plus(rot.plus(EDN_TO_NWU));
return EDN_TO_NWU.inverse().rotateBy(rot.rotateBy(EDN_TO_NWU));
}
/**
@@ -279,7 +278,7 @@ public final class OpenCVHelp {
* @return The converted rotation in the EDN coordinate system
*/
private static Rotation3d rotationNWUtoEDN(Rotation3d rot) {
return NWU_TO_EDN.unaryMinus().plus(rot.plus(NWU_TO_EDN));
return NWU_TO_EDN.inverse().rotateBy(rot.rotateBy(NWU_TO_EDN));
}
/**

View File

@@ -46,7 +46,7 @@ public class RotTrlTransform3d {
}
public RotTrlTransform3d(Pose3d initial, Pose3d last) {
this.rot = last.getRotation().minus(initial.getRotation());
this.rot = last.getRotation().relativeTo(initial.getRotation());
this.trl = last.getTranslation().minus(initial.getTranslation().rotateBy(rot));
}
@@ -83,7 +83,7 @@ public class RotTrlTransform3d {
* @return The inverse transformation
*/
public RotTrlTransform3d inverse() {
var inverseRot = rot.unaryMinus();
var inverseRot = rot.inverse();
var inverseTrl = trl.rotateBy(inverseRot).unaryMinus();
return new RotTrlTransform3d(inverseRot, inverseTrl);
}
@@ -124,7 +124,7 @@ public class RotTrlTransform3d {
}
public Rotation3d apply(Rotation3d rot) {
return rot.plus(this.rot);
return rot.rotateBy(this.rot);
}
public List<Rotation3d> applyRots(List<Rotation3d> rots) {

View File

@@ -106,7 +106,8 @@ void wpi::tsp::TimeSyncClient::Tick() {
m_lastPing = ping;
}
void wpi::tsp::TimeSyncClient::UdpCallback(wpi::net::uv::Buffer& buf, size_t nbytes,
void wpi::tsp::TimeSyncClient::UdpCallback(wpi::net::uv::Buffer& buf,
size_t nbytes,
const sockaddr& sender,
unsigned flags) {
uint64_t pong_local_time = m_timeProvider();
@@ -183,8 +184,9 @@ void wpi::tsp::TimeSyncClient::Start() {
using namespace std::chrono_literals;
m_pingTimer->timeout.connect(&wpi::tsp::TimeSyncClient::Tick, this);
m_loopRunner.ExecSync(
[this](wpi::net::uv::Loop&) { m_pingTimer->Start(m_loopDelay, m_loopDelay); });
m_loopRunner.ExecSync([this](wpi::net::uv::Loop&) {
m_pingTimer->Start(m_loopDelay, m_loopDelay);
});
}
void wpi::tsp::TimeSyncClient::Stop() { m_loopRunner.Stop(); }

View File

@@ -23,11 +23,12 @@
#include <wpi/net/UDPClient.hpp>
#include <wpi/net/uv/util.hpp>
#include <wpi/nt/ntcore_cpp.hpp>
#include <wpi/util/Logger.hpp>
#include <wpi/util/print.hpp>
#include <wpi/util/struct/Struct.hpp>
#include <wpi/nt/ntcore_cpp.hpp>
#include "net/TimeSyncStructs.h"
static void ServerLoggerFunc(unsigned int level, const char* file,
unsigned int line, const char* msg) {

View File

@@ -25,7 +25,7 @@
#include <Eigen/LU>
#include <fmt/core.h>
#include <wpi/math/fmt/Eigen.hpp>
#include <wpi/util/timestamp.h>
#include <wpi/util/timestamp.hpp>
#include "../generate/constrained_solvepnp_10_tags_fixed.h"
#include "../generate/constrained_solvepnp_10_tags_free.h"
@@ -47,6 +47,7 @@
#include "../generate/constrained_solvepnp_8_tags_free.h"
#include "../generate/constrained_solvepnp_9_tags_fixed.h"
#include "../generate/constrained_solvepnp_9_tags_free.h"
#include "wpi/nt/ntcore_cpp.hpp"
constexpr bool VERBOSE = false;
@@ -225,7 +226,7 @@ constrained_solvepnp::do_optimization(
constexpr double ERROR_TOL = 1e-4;
for (int iter = 0; iter < 100; iter++) {
auto iter_start = wpi::util::Now();
auto iter_start = wpi::nt::Now();
// Check for diverging iterates
if (x.template lpNorm<Eigen::Infinity>() > 1e20 || !x.allFinite()) {
@@ -343,7 +344,7 @@ constrained_solvepnp::do_optimization(
}
}
auto iter_end = wpi::util::Now();
auto iter_end = wpi::nt::Now();
if constexpr (VERBOSE) {
fmt::println(
"{}: {} uS, ‖∇J‖={}, α={} ({} refinement steps), {} regularization "

View File

@@ -191,8 +191,8 @@ std::optional<photon::PnpResult> EstimateRobotPoseConstrainedSolvePNP(
guess2.X().value(), guess2.Y().value(),
guess2.Rotation().Radians().value()};
wpi::util::expected<constrained_solvepnp::RobotStateMat, slp::ExitStatus> result =
constrained_solvepnp::do_optimization(
wpi::util::expected<constrained_solvepnp::RobotStateMat, slp::ExitStatus>
result = constrained_solvepnp::do_optimization(
headingFree, knownTags.size(), cameraCal, robotToCamera, guessMat,
field2points, pointObservations, gyroTheta.Radians().value(),
gyroErrorScaleFac);
@@ -203,7 +203,8 @@ std::optional<photon::PnpResult> EstimateRobotPoseConstrainedSolvePNP(
photon::PnpResult res{};
res.best = wpi::math::Transform3d{wpi::math::Transform2d{
wpi::units::meter_t{result.value()[0]}, wpi::units::meter_t{result.value()[1]},
wpi::units::meter_t{result.value()[0]},
wpi::units::meter_t{result.value()[1]},
wpi::math::Rotation2d{wpi::units::radian_t{result.value()[2]}}}};
return res;

View File

@@ -45,8 +45,8 @@ class TimeSyncServer {
std::thread m_listener;
private:
void UdpCallback(wpi::net::uv::Buffer& buf, size_t nbytes, const sockaddr& sender,
unsigned flags);
void UdpCallback(wpi::net::uv::Buffer& buf, size_t nbytes,
const sockaddr& sender, unsigned flags);
public:
explicit TimeSyncServer(int port = 5810);

View File

@@ -43,7 +43,7 @@ class CameraTargetRelation {
camToTarg(wpi::math::Transform3d{cameraPose, targetPose}),
camToTargDist(camToTarg.Translation().Norm()),
camToTargDistXY(wpi::units::math::hypot(camToTarg.Translation().X(),
camToTarg.Translation().Y())),
camToTarg.Translation().Y())),
camToTargYaw(wpi::math::Rotation2d{camToTarg.X().to<double>(),
camToTarg.Y().to<double>()}),
camToTargPitch(wpi::math::Rotation2d{camToTargDistXY.to<double>(),

View File

@@ -64,7 +64,7 @@ static wpi::math::Translation3d TranslationNWUtoEDN(
static wpi::math::Rotation3d RotationNWUtoEDN(
const wpi::math::Rotation3d& rot) {
return -NWU_TO_EDN + (rot + NWU_TO_EDN);
return NWU_TO_EDN.Inverse().RotateBy(rot.RotateBy(NWU_TO_EDN));
}
static std::vector<cv::Point3f> TranslationToTVec(
@@ -186,7 +186,7 @@ static wpi::math::Translation3d TranslationEDNToNWU(
static wpi::math::Rotation3d RotationEDNToNWU(
const wpi::math::Rotation3d& rot) {
return -EDN_TO_NWU + (rot + EDN_TO_NWU);
return EDN_TO_NWU.Inverse().RotateBy(rot.RotateBy(EDN_TO_NWU));
}
static wpi::math::Translation3d TVecToTranslation(const cv::Mat& tvecInput) {
@@ -194,9 +194,9 @@ static wpi::math::Translation3d TVecToTranslation(const cv::Mat& tvecInput) {
cv::Mat wrapped{tvecInput.rows, tvecInput.cols, CV_32F};
tvecInput.convertTo(wrapped, CV_32F);
data = wrapped.at<cv::Vec3f>(cv::Point{0, 0});
return TranslationEDNToNWU(wpi::math::Translation3d{wpi::units::meter_t{data[0]},
wpi::units::meter_t{data[1]},
wpi::units::meter_t{data[2]}});
return TranslationEDNToNWU(wpi::math::Translation3d{
wpi::units::meter_t{data[0]}, wpi::units::meter_t{data[1]},
wpi::units::meter_t{data[2]}});
}
static wpi::math::Rotation3d RVecToRotation(const cv::Mat& rvecInput) {

View File

@@ -32,9 +32,10 @@ class RotTrlTransform3d {
RotTrlTransform3d(const wpi::math::Pose3d& initial,
const wpi::math::Pose3d& last)
: trl{last.Translation() - initial.Translation().RotateBy(
last.Rotation() - initial.Rotation())},
rot{last.Rotation() - initial.Rotation()} {}
: trl{last.Translation() -
initial.Translation().RotateBy(
last.Rotation().RelativeTo(initial.Rotation()))},
rot{last.Rotation().RelativeTo(initial.Rotation())} {}
explicit RotTrlTransform3d(const wpi::math::Transform3d& trf)
: RotTrlTransform3d(trf.Rotation(), trf.Translation()) {}
RotTrlTransform3d()
@@ -46,7 +47,7 @@ class RotTrlTransform3d {
}
RotTrlTransform3d Inverse() const {
wpi::math::Rotation3d invRot = -rot;
wpi::math::Rotation3d invRot = rot.Inverse();
wpi::math::Translation3d invTrl = -(trl.RotateBy(invRot));
return RotTrlTransform3d{invRot, invTrl};
}
@@ -75,7 +76,7 @@ class RotTrlTransform3d {
}
wpi::math::Rotation3d Apply(const wpi::math::Rotation3d& rotToApply) const {
return rotToApply + rot;
return rotToApply.RotateBy(rot);
}
std::vector<wpi::math::Rotation3d> ApplyTrls(

View File

@@ -41,11 +41,12 @@ extern "C" {
* Signature: (ZI[D[D[D[D[DDD)[D
*/
JNIEXPORT jdoubleArray JNICALL
Java_org_photonvision_jni_ConstrainedSolvepnpJni_do_1optimization(
JNIEnv* env, jclass, jboolean headingFree, jint nTags,
jdoubleArray cameraCal, jdoubleArray robot2camera, jdoubleArray xGuess,
jdoubleArray field2points, jdoubleArray pointObservations, jdouble gyro_θ,
jdouble gyro_error_scale_fac) {
Java_org_photonvision_jni_ConstrainedSolvepnpJni_do_1optimization
(JNIEnv* env, jclass, jboolean headingFree, jint nTags,
jdoubleArray cameraCal, jdoubleArray robot2camera, jdoubleArray xGuess,
jdoubleArray field2points, jdoubleArray pointObservations, jdouble gyro_θ,
jdouble gyro_error_scale_fac)
{
auto cameraCalVec = convertJDoubleArray(env, cameraCal);
auto robot2cameraVec = convertJDoubleArray(env, robot2camera);
auto xGuessVec = convertJDoubleArray(env, xGuess);

View File

@@ -18,10 +18,11 @@
#include <string>
#include <opencv2/core/mat.hpp>
#include <wpi/util/RawFrame.hpp>
#include <wpi/util/jni_util.hpp>
#include "org_photonvision_jni_CscoreExtras.h"
#include "wpi/cs/cscore_raw.h"
#include "wpi/cs/cscore_raw.hpp"
// from wpilib, licensed under the wpilib BSD license
using namespace wpi::util::java;

View File

@@ -15,8 +15,8 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#include <frc/fmt/Eigen.h>
#include <gtest/gtest.h>
#include <wpi/math/fmt/Eigen.hpp>
#include <wpi/util/print.hpp>
#include <wpi/util/timestamp.h>
@@ -159,15 +159,15 @@ void print_cost(casadi_real robot_x, casadi_real robot_y,
x_guess << robot_x, robot_y, robot_theta;
for (int i = 0; i < 200; i++) {
auto start = wpi::util::Now();
auto start = WPI_Now();
auto x_out = constrained_solvepnp::do_optimization(
true, TAG_COUNT,
constrained_solvepnp::CameraCalibration{fx, fy, cx, cy}, robot2camera,
x_guess, field2points, point_observations, 0, 0);
auto end = wpi::util::Now();
auto end = WPI_Now();
wpi::println("{},{},{}", i, static_cast<bool>(x_out), end - start);
wpi::println(
wpi::util::println("{},{},{}", i, static_cast<bool>(x_out), end - start);
wpi::util::println(
"Solution: {}",
x_out.value_or(constrained_solvepnp::RobotStateMat::Identity()));
// std::cout << "iter "

View File

@@ -11,7 +11,7 @@ repositories {
wpi.maven.useLocal = false
wpi.maven.useDevelopment = false
wpi.versions.wpilibVersion = "2027.0.+"
wpi.versions.wpilibVersion = "2027.0.0-alpha-4"
// Define my targets (SystemCore) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.

View File

@@ -4,7 +4,7 @@ pluginManagement {
repositories {
mavenLocal()
gradlePluginPortal()
String frcYear = '2027_alpha1'
String frcYear = '2027_alpha4'
File frcHome
if (OperatingSystem.current().isWindows()) {
String publicFolder = System.getenv('PUBLIC')

View File

@@ -124,7 +124,8 @@ void Robot::SimulationPeriodic() {
wpi::sim::BatterySim::Calculate({totalCurrent});
// Using max(0.1, voltage) here isn't a *physically correct* solution,
// but it avoids problems with battery voltage measuring 0.
wpi::sim::RoboRioSim::SetVInVoltage(wpi::units::math::max(0.1_V, loadedBattVolts));
wpi::sim::RoboRioSim::SetVInVoltage(
wpi::units::math::max(0.1_V, loadedBattVolts));
}
#ifndef RUNNING_FRC_TESTS

View File

@@ -151,7 +151,8 @@ void SwerveDrive::Log() {
wpi::SmartDashboard::PutNumber(table + "VY", chassisSpeeds.vy.to<double>());
wpi::SmartDashboard::PutNumber(
table + "Omega Degrees",
chassisSpeeds.omega.convert<wpi::units::degrees_per_second>().to<double>());
chassisSpeeds.omega.convert<wpi::units::degrees_per_second>()
.to<double>());
wpi::SmartDashboard::PutNumber(table + "Target VX",
targetChassisSpeeds.vx.to<double>());
wpi::SmartDashboard::PutNumber(table + "Target VY",
@@ -207,4 +208,6 @@ wpi::math::Pose2d SwerveDrive::GetSimPose() const {
return swerveDriveSim.GetPose();
}
wpi::units::ampere_t SwerveDrive::GetCurrentDraw() const { return totalCurrentDraw; }
wpi::units::ampere_t SwerveDrive::GetCurrentDraw() const {
return totalCurrentDraw;
}

View File

@@ -60,11 +60,12 @@ SwerveDriveSim::SwerveDriveSim(
steerFF.GetKs(), steerMotor, steerGearing, kinematics) {}
SwerveDriveSim::SwerveDriveSim(
const wpi::math::LinearSystem<2, 1, 2>& drivePlant, wpi::units::volt_t driveKs,
const wpi::math::DCMotor& driveMotor, double driveGearing,
wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant, wpi::units::volt_t steerKs,
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::LinearSystem<2, 1, 2>& drivePlant,
wpi::units::volt_t driveKs, const wpi::math::DCMotor& driveMotor,
double driveGearing, wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant,
wpi::units::volt_t steerKs, const wpi::math::DCMotor& steerMotor,
double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics)
: drivePlant(drivePlant),
driveKs(driveKs),
@@ -230,7 +231,9 @@ SwerveDriveSim::GetSteerStates() const {
return steerStates;
}
wpi::units::radians_per_second_t SwerveDriveSim::GetOmega() const { return omega; }
wpi::units::radians_per_second_t SwerveDriveSim::GetOmega() const {
return omega;
}
wpi::units::ampere_t SwerveDriveSim::GetCurrentDraw(
const wpi::math::DCMotor& motor, wpi::units::radians_per_second_t velocity,
@@ -245,8 +248,8 @@ wpi::units::ampere_t SwerveDriveSim::GetCurrentDraw(
return retVal;
}
std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetDriveCurrentDraw()
const {
std::array<wpi::units::ampere_t, numModules>
SwerveDriveSim::GetDriveCurrentDraw() const {
std::array<wpi::units::ampere_t, numModules> currents;
for (int i = 0; i < numModules; i++) {
wpi::units::radians_per_second_t speed =
@@ -258,8 +261,8 @@ std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetDriveCurrentDraw
return currents;
}
std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetSteerCurrentDraw()
const {
std::array<wpi::units::ampere_t, numModules>
SwerveDriveSim::GetSteerCurrentDraw() const {
std::array<wpi::units::ampere_t, numModules> currents;
for (int i = 0; i < numModules; i++) {
wpi::units::radians_per_second_t speed =

View File

@@ -71,7 +71,8 @@ void SwerveModule::SetDesiredState(wpi::math::SwerveModuleState newState,
}
wpi::math::Rotation2d SwerveModule::GetAbsoluteHeading() const {
return wpi::math::Rotation2d{wpi::units::radian_t{steerEncoder.GetDistance()}};
return wpi::math::Rotation2d{
wpi::units::radian_t{steerEncoder.GetDistance()}};
}
wpi::math::SwerveModuleState SwerveModule::GetState() const {
@@ -132,8 +133,8 @@ void SwerveModule::Log() {
void SwerveModule::SimulationUpdate(
wpi::units::meter_t driveEncoderDist,
wpi::units::meters_per_second_t driveEncoderRate, wpi::units::ampere_t driveCurrent,
wpi::units::radian_t steerEncoderDist,
wpi::units::meters_per_second_t driveEncoderRate,
wpi::units::ampere_t driveCurrent, wpi::units::radian_t steerEncoderDist,
wpi::units::radians_per_second_t steerEncoderRate,
wpi::units::ampere_t steerCurrent) {
driveEncoderSim.SetDistance(driveEncoderDist.to<double>());

View File

@@ -58,10 +58,11 @@ inline constexpr wpi::units::meter_t kTrackLength{18.5_in};
inline constexpr wpi::units::meter_t kRobotWidth{25_in + 3.25_in * 2};
inline constexpr wpi::units::meter_t kRobotLength{25_in + 3.25_in * 2};
inline constexpr wpi::units::meters_per_second_t kMaxLinearSpeed{15.5_fps};
inline constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{720_deg_per_s};
inline constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
720_deg_per_s};
inline constexpr wpi::units::meter_t kWheelDiameter{4_in};
inline constexpr wpi::units::meter_t kWheelCircumference{kWheelDiameter *
std::numbers::pi};
std::numbers::pi};
inline constexpr double kDriveGearRatio = 6.75;
inline constexpr double kSteerGearRatio = 12.8;
@@ -101,8 +102,8 @@ struct ModuleConstants {
ModuleConstants(int moduleNum, int driveMotorId, int driveEncoderA,
int driveEncoderB, int steerMotorId, int steerEncoderA,
int steerEncoderB, double angleOffset, wpi::units::meter_t xOffset,
wpi::units::meter_t yOffset)
int steerEncoderB, double angleOffset,
wpi::units::meter_t xOffset, wpi::units::meter_t yOffset)
: moduleNum(moduleNum),
driveMotorId(driveMotorId),
driveEncoderA(driveEncoderA),

View File

@@ -35,7 +35,8 @@ class SwerveDrive {
public:
SwerveDrive();
void Periodic();
void Drive(wpi::units::meters_per_second_t vx, wpi::units::meters_per_second_t vy,
void Drive(wpi::units::meters_per_second_t vx,
wpi::units::meters_per_second_t vy,
wpi::units::radians_per_second_t omega);
void SetChassisSpeeds(const wpi::math::ChassisSpeeds& targetChassisSpeeds,
bool openLoop, bool steerInPlace);

View File

@@ -44,11 +44,12 @@ class SwerveDriveSim {
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics);
SwerveDriveSim(
const wpi::math::LinearSystem<2, 1, 2>& drivePlant, wpi::units::volt_t driveKs,
const wpi::math::DCMotor& driveMotor, double driveGearing,
wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant, wpi::units::volt_t steerKs,
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::LinearSystem<2, 1, 2>& drivePlant,
wpi::units::volt_t driveKs, const wpi::math::DCMotor& driveMotor,
double driveGearing, wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant,
wpi::units::volt_t steerKs, const wpi::math::DCMotor& steerMotor,
double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics);
void SetDriveInputs(const std::array<wpi::units::volt_t, numModules>& inputs);
void SetSteerInputs(const std::array<wpi::units::volt_t, numModules>& inputs);
@@ -75,9 +76,9 @@ class SwerveDriveSim {
std::array<Eigen::Matrix<double, 2, 1>, numModules> GetSteerStates() const;
wpi::units::radians_per_second_t GetOmega() const;
wpi::units::ampere_t GetCurrentDraw(const wpi::math::DCMotor& motor,
wpi::units::radians_per_second_t velocity,
wpi::units::volt_t inputVolts,
wpi::units::volt_t batteryVolts) const;
wpi::units::radians_per_second_t velocity,
wpi::units::volt_t inputVolts,
wpi::units::volt_t batteryVolts) const;
std::array<wpi::units::ampere_t, numModules> GetDriveCurrentDraw() const;
std::array<wpi::units::ampere_t, numModules> GetSteerCurrentDraw() const;
wpi::units::ampere_t GetTotalCurrentDraw() const;

View File

@@ -11,7 +11,7 @@ repositories {
wpi.maven.useLocal = false
wpi.maven.useDevelopment = false
wpi.versions.wpilibVersion = "2027.0.+"
wpi.versions.wpilibVersion = "2027.0.0-alpha-4"
// Define my targets (SystemCore) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.

View File

@@ -4,7 +4,7 @@ pluginManagement {
repositories {
mavenLocal()
gradlePluginPortal()
String frcYear = '2027_alpha1'
String frcYear = '2027_alpha4'
File frcHome
if (OperatingSystem.current().isWindows()) {
String publicFolder = System.getenv('PUBLIC')

View File

@@ -115,7 +115,8 @@ void Robot::SimulationPeriodic() {
wpi::sim::BatterySim::Calculate({totalCurrent});
// Using max(0.1, voltage) here isn't a *physically correct* solution,
// but it avoids problems with battery voltage measuring 0.
wpi::sim::RoboRioSim::SetVInVoltage(wpi::units::math::max(0.1_V, loadedBattVolts));
wpi::sim::RoboRioSim::SetVInVoltage(
wpi::units::math::max(0.1_V, loadedBattVolts));
}
#ifndef RUNNING_FRC_TESTS

View File

@@ -151,7 +151,8 @@ void SwerveDrive::Log() {
wpi::SmartDashboard::PutNumber(table + "VY", chassisSpeeds.vy.to<double>());
wpi::SmartDashboard::PutNumber(
table + "Omega Degrees",
chassisSpeeds.omega.convert<wpi::units::degrees_per_second>().to<double>());
chassisSpeeds.omega.convert<wpi::units::degrees_per_second>()
.to<double>());
wpi::SmartDashboard::PutNumber(table + "Target VX",
targetChassisSpeeds.vx.to<double>());
wpi::SmartDashboard::PutNumber(table + "Target VY",
@@ -207,4 +208,6 @@ wpi::math::Pose2d SwerveDrive::GetSimPose() const {
return swerveDriveSim.GetPose();
}
wpi::units::ampere_t SwerveDrive::GetCurrentDraw() const { return totalCurrentDraw; }
wpi::units::ampere_t SwerveDrive::GetCurrentDraw() const {
return totalCurrentDraw;
}

View File

@@ -60,11 +60,12 @@ SwerveDriveSim::SwerveDriveSim(
steerFF.GetKs(), steerMotor, steerGearing, kinematics) {}
SwerveDriveSim::SwerveDriveSim(
const wpi::math::LinearSystem<2, 1, 2>& drivePlant, wpi::units::volt_t driveKs,
const wpi::math::DCMotor& driveMotor, double driveGearing,
wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant, wpi::units::volt_t steerKs,
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::LinearSystem<2, 1, 2>& drivePlant,
wpi::units::volt_t driveKs, const wpi::math::DCMotor& driveMotor,
double driveGearing, wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant,
wpi::units::volt_t steerKs, const wpi::math::DCMotor& steerMotor,
double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics)
: drivePlant(drivePlant),
driveKs(driveKs),
@@ -230,7 +231,9 @@ SwerveDriveSim::GetSteerStates() const {
return steerStates;
}
wpi::units::radians_per_second_t SwerveDriveSim::GetOmega() const { return omega; }
wpi::units::radians_per_second_t SwerveDriveSim::GetOmega() const {
return omega;
}
wpi::units::ampere_t SwerveDriveSim::GetCurrentDraw(
const wpi::math::DCMotor& motor, wpi::units::radians_per_second_t velocity,
@@ -245,8 +248,8 @@ wpi::units::ampere_t SwerveDriveSim::GetCurrentDraw(
return retVal;
}
std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetDriveCurrentDraw()
const {
std::array<wpi::units::ampere_t, numModules>
SwerveDriveSim::GetDriveCurrentDraw() const {
std::array<wpi::units::ampere_t, numModules> currents;
for (int i = 0; i < numModules; i++) {
wpi::units::radians_per_second_t speed =
@@ -258,8 +261,8 @@ std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetDriveCurrentDraw
return currents;
}
std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetSteerCurrentDraw()
const {
std::array<wpi::units::ampere_t, numModules>
SwerveDriveSim::GetSteerCurrentDraw() const {
std::array<wpi::units::ampere_t, numModules> currents;
for (int i = 0; i < numModules; i++) {
wpi::units::radians_per_second_t speed =

View File

@@ -71,7 +71,8 @@ void SwerveModule::SetDesiredState(wpi::math::SwerveModuleState newState,
}
wpi::math::Rotation2d SwerveModule::GetAbsoluteHeading() const {
return wpi::math::Rotation2d{wpi::units::radian_t{steerEncoder.GetDistance()}};
return wpi::math::Rotation2d{
wpi::units::radian_t{steerEncoder.GetDistance()}};
}
wpi::math::SwerveModuleState SwerveModule::GetState() const {
@@ -132,8 +133,8 @@ void SwerveModule::Log() {
void SwerveModule::SimulationUpdate(
wpi::units::meter_t driveEncoderDist,
wpi::units::meters_per_second_t driveEncoderRate, wpi::units::ampere_t driveCurrent,
wpi::units::radian_t steerEncoderDist,
wpi::units::meters_per_second_t driveEncoderRate,
wpi::units::ampere_t driveCurrent, wpi::units::radian_t steerEncoderDist,
wpi::units::radians_per_second_t steerEncoderRate,
wpi::units::ampere_t steerCurrent) {
driveEncoderSim.SetDistance(driveEncoderDist.to<double>());

View File

@@ -58,10 +58,11 @@ inline constexpr wpi::units::meter_t kTrackLength{18.5_in};
inline constexpr wpi::units::meter_t kRobotWidth{25_in + 3.25_in * 2};
inline constexpr wpi::units::meter_t kRobotLength{25_in + 3.25_in * 2};
inline constexpr wpi::units::meters_per_second_t kMaxLinearSpeed{15.5_fps};
inline constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{720_deg_per_s};
inline constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
720_deg_per_s};
inline constexpr wpi::units::meter_t kWheelDiameter{4_in};
inline constexpr wpi::units::meter_t kWheelCircumference{kWheelDiameter *
std::numbers::pi};
std::numbers::pi};
inline constexpr double kDriveGearRatio = 6.75;
inline constexpr double kSteerGearRatio = 12.8;
@@ -101,8 +102,8 @@ struct ModuleConstants {
ModuleConstants(int moduleNum, int driveMotorId, int driveEncoderA,
int driveEncoderB, int steerMotorId, int steerEncoderA,
int steerEncoderB, double angleOffset, wpi::units::meter_t xOffset,
wpi::units::meter_t yOffset)
int steerEncoderB, double angleOffset,
wpi::units::meter_t xOffset, wpi::units::meter_t yOffset)
: moduleNum(moduleNum),
driveMotorId(driveMotorId),
driveEncoderA(driveEncoderA),

View File

@@ -37,7 +37,8 @@ class SwerveDrive {
public:
SwerveDrive();
void Periodic();
void Drive(wpi::units::meters_per_second_t vx, wpi::units::meters_per_second_t vy,
void Drive(wpi::units::meters_per_second_t vx,
wpi::units::meters_per_second_t vy,
wpi::units::radians_per_second_t omega);
void SetChassisSpeeds(const wpi::math::ChassisSpeeds& targetChassisSpeeds,
bool openLoop, bool steerInPlace);

View File

@@ -44,11 +44,12 @@ class SwerveDriveSim {
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics);
SwerveDriveSim(
const wpi::math::LinearSystem<2, 1, 2>& drivePlant, wpi::units::volt_t driveKs,
const wpi::math::DCMotor& driveMotor, double driveGearing,
wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant, wpi::units::volt_t steerKs,
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::LinearSystem<2, 1, 2>& drivePlant,
wpi::units::volt_t driveKs, const wpi::math::DCMotor& driveMotor,
double driveGearing, wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant,
wpi::units::volt_t steerKs, const wpi::math::DCMotor& steerMotor,
double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics);
void SetDriveInputs(const std::array<wpi::units::volt_t, numModules>& inputs);
void SetSteerInputs(const std::array<wpi::units::volt_t, numModules>& inputs);
@@ -75,9 +76,9 @@ class SwerveDriveSim {
std::array<Eigen::Matrix<double, 2, 1>, numModules> GetSteerStates() const;
wpi::units::radians_per_second_t GetOmega() const;
wpi::units::ampere_t GetCurrentDraw(const wpi::math::DCMotor& motor,
wpi::units::radians_per_second_t velocity,
wpi::units::volt_t inputVolts,
wpi::units::volt_t batteryVolts) const;
wpi::units::radians_per_second_t velocity,
wpi::units::volt_t inputVolts,
wpi::units::volt_t batteryVolts) const;
std::array<wpi::units::ampere_t, numModules> GetDriveCurrentDraw() const;
std::array<wpi::units::ampere_t, numModules> GetSteerCurrentDraw() const;
wpi::units::ampere_t GetTotalCurrentDraw() const;

View File

@@ -1,6 +1,6 @@
distributionBase=GRADLE_USER_HOME
distributionPath=wrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-9.2.0-bin.zip
networkTimeout=10000
validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME

View File

@@ -11,7 +11,7 @@ repositories {
wpi.maven.useLocal = false
wpi.maven.useDevelopment = false
wpi.versions.wpilibVersion = "2027.0.+"
wpi.versions.wpilibVersion = "2027.0.0-alpha-4"
// Define my targets (SystemCore) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.

View File

@@ -4,7 +4,7 @@ pluginManagement {
repositories {
mavenLocal()
gradlePluginPortal()
String frcYear = '2027_alpha1'
String frcYear = '2027_alpha4'
File frcHome
if (OperatingSystem.current().isWindows()) {
String publicFolder = System.getenv('PUBLIC')

View File

@@ -98,7 +98,8 @@ void Robot::SimulationPeriodic() {
// Using max(0.1, voltage) here isn't a *physically correct* solution,
// but it avoids problems with battery voltage measuring 0.
wpi::sim::RoboRioSim::SetVInVoltage(wpi::units::math::max(0.1_V, loadedBattVolts));
wpi::sim::RoboRioSim::SetVInVoltage(
wpi::units::math::max(0.1_V, loadedBattVolts));
}
#ifndef RUNNING_FRC_TESTS

View File

@@ -35,10 +35,10 @@ void GamepieceLauncher::setRunning(bool shouldRun) {
void GamepieceLauncher::periodic() {
// Calculate the maximum RPM
double maxRPM =
wpi::units::radians_per_second_t(wpi::math::DCMotor::Falcon500(1).freeSpeed)
.to<double>() *
60 / (2 * std::numbers::pi);
double maxRPM = wpi::units::radians_per_second_t(
wpi::math::DCMotor::Falcon500(1).freeSpeed)
.to<double>() *
60 / (2 * std::numbers::pi);
curMotorCmd = curDesSpd / maxRPM;
curMotorCmd = std::clamp(curMotorCmd, 0.0, 1.0);
motor->Set(curMotorCmd);

View File

@@ -81,7 +81,8 @@ void SwerveDrive::SetModuleStates(
void SwerveDrive::Stop() { Drive(0_mps, 0_mps, 0_rad_per_s); }
void SwerveDrive::AddVisionMeasurement(
const wpi::math::Pose2d& visionMeasurement, wpi::units::second_t timestamp) {
const wpi::math::Pose2d& visionMeasurement,
wpi::units::second_t timestamp) {
poseEstimator.AddVisionMeasurement(visionMeasurement, timestamp);
}
@@ -163,7 +164,8 @@ void SwerveDrive::Log() {
wpi::SmartDashboard::PutNumber(table + "VY", chassisSpeeds.vy.to<double>());
wpi::SmartDashboard::PutNumber(
table + "Omega Degrees",
chassisSpeeds.omega.convert<wpi::units::degrees_per_second>().to<double>());
chassisSpeeds.omega.convert<wpi::units::degrees_per_second>()
.to<double>());
wpi::SmartDashboard::PutNumber(table + "Target VX",
targetChassisSpeeds.vx.to<double>());
wpi::SmartDashboard::PutNumber(table + "Target VY",
@@ -219,4 +221,6 @@ wpi::math::Pose2d SwerveDrive::GetSimPose() const {
return swerveDriveSim.GetPose();
}
wpi::units::ampere_t SwerveDrive::GetCurrentDraw() const { return totalCurrentDraw; }
wpi::units::ampere_t SwerveDrive::GetCurrentDraw() const {
return totalCurrentDraw;
}

View File

@@ -60,11 +60,12 @@ SwerveDriveSim::SwerveDriveSim(
steerFF.GetKs(), steerMotor, steerGearing, kinematics) {}
SwerveDriveSim::SwerveDriveSim(
const wpi::math::LinearSystem<2, 1, 2>& drivePlant, wpi::units::volt_t driveKs,
const wpi::math::DCMotor& driveMotor, double driveGearing,
wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant, wpi::units::volt_t steerKs,
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::LinearSystem<2, 1, 2>& drivePlant,
wpi::units::volt_t driveKs, const wpi::math::DCMotor& driveMotor,
double driveGearing, wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant,
wpi::units::volt_t steerKs, const wpi::math::DCMotor& steerMotor,
double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics)
: drivePlant(drivePlant),
driveKs(driveKs),
@@ -230,7 +231,9 @@ SwerveDriveSim::GetSteerStates() const {
return steerStates;
}
wpi::units::radians_per_second_t SwerveDriveSim::GetOmega() const { return omega; }
wpi::units::radians_per_second_t SwerveDriveSim::GetOmega() const {
return omega;
}
wpi::units::ampere_t SwerveDriveSim::GetCurrentDraw(
const wpi::math::DCMotor& motor, wpi::units::radians_per_second_t velocity,
@@ -245,8 +248,8 @@ wpi::units::ampere_t SwerveDriveSim::GetCurrentDraw(
return retVal;
}
std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetDriveCurrentDraw()
const {
std::array<wpi::units::ampere_t, numModules>
SwerveDriveSim::GetDriveCurrentDraw() const {
std::array<wpi::units::ampere_t, numModules> currents;
for (int i = 0; i < numModules; i++) {
wpi::units::radians_per_second_t speed =
@@ -258,8 +261,8 @@ std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetDriveCurrentDraw
return currents;
}
std::array<wpi::units::ampere_t, numModules> SwerveDriveSim::GetSteerCurrentDraw()
const {
std::array<wpi::units::ampere_t, numModules>
SwerveDriveSim::GetSteerCurrentDraw() const {
std::array<wpi::units::ampere_t, numModules> currents;
for (int i = 0; i < numModules; i++) {
wpi::units::radians_per_second_t speed =

View File

@@ -71,7 +71,8 @@ void SwerveModule::SetDesiredState(wpi::math::SwerveModuleState newState,
}
wpi::math::Rotation2d SwerveModule::GetAbsoluteHeading() const {
return wpi::math::Rotation2d{wpi::units::radian_t{steerEncoder.GetDistance()}};
return wpi::math::Rotation2d{
wpi::units::radian_t{steerEncoder.GetDistance()}};
}
wpi::math::SwerveModuleState SwerveModule::GetState() const {
@@ -132,8 +133,8 @@ void SwerveModule::Log() {
void SwerveModule::SimulationUpdate(
wpi::units::meter_t driveEncoderDist,
wpi::units::meters_per_second_t driveEncoderRate, wpi::units::ampere_t driveCurrent,
wpi::units::radian_t steerEncoderDist,
wpi::units::meters_per_second_t driveEncoderRate,
wpi::units::ampere_t driveCurrent, wpi::units::radian_t steerEncoderDist,
wpi::units::radians_per_second_t steerEncoderRate,
wpi::units::ampere_t steerCurrent) {
driveEncoderSim.SetDistance(driveEncoderDist.to<double>());

View File

@@ -58,10 +58,11 @@ inline constexpr wpi::units::meter_t kTrackLength{18.5_in};
inline constexpr wpi::units::meter_t kRobotWidth{25_in + 3.25_in * 2};
inline constexpr wpi::units::meter_t kRobotLength{25_in + 3.25_in * 2};
inline constexpr wpi::units::meters_per_second_t kMaxLinearSpeed{15.5_fps};
inline constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{720_deg_per_s};
inline constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
720_deg_per_s};
inline constexpr wpi::units::meter_t kWheelDiameter{4_in};
inline constexpr wpi::units::meter_t kWheelCircumference{kWheelDiameter *
std::numbers::pi};
std::numbers::pi};
inline constexpr double kDriveGearRatio = 6.75;
inline constexpr double kSteerGearRatio = 12.8;
@@ -101,8 +102,8 @@ struct ModuleConstants {
ModuleConstants(int moduleNum, int driveMotorId, int driveEncoderA,
int driveEncoderB, int steerMotorId, int steerEncoderA,
int steerEncoderB, double angleOffset, wpi::units::meter_t xOffset,
wpi::units::meter_t yOffset)
int steerEncoderB, double angleOffset,
wpi::units::meter_t xOffset, wpi::units::meter_t yOffset)
: moduleNum(moduleNum),
driveMotorId(driveMotorId),
driveEncoderA(driveEncoderA),

View File

@@ -51,7 +51,8 @@ class Robot : public wpi::TimedRobot {
private:
SwerveDrive drivetrain{};
Vision vision{[=, this](wpi::math::Pose2d pose, wpi::units::second_t timestamp,
Vision vision{[=, this](wpi::math::Pose2d pose,
wpi::units::second_t timestamp,
Eigen::Matrix<double, 3, 1> stddevs) {
drivetrain.AddVisionMeasurement(pose, timestamp, stddevs);
}};

View File

@@ -50,8 +50,8 @@ class GamepieceLauncher {
double curDesSpd = 0.0;
double curMotorCmd = 0.0;
static constexpr wpi::units::kilogram_square_meter_t kFlywheelMomentOfInertia =
0.5 * 1.5_lb * 4_in * 4_in;
static constexpr wpi::units::kilogram_square_meter_t
kFlywheelMomentOfInertia = 0.5 * 1.5_lb * 4_in * 4_in;
wpi::math::DCMotor m_gearbox = wpi::math::DCMotor::Falcon500(1);
wpi::math::LinearSystem<1, 1, 1> m_plant{

View File

@@ -37,7 +37,8 @@ class SwerveDrive {
public:
SwerveDrive();
void Periodic();
void Drive(wpi::units::meters_per_second_t vx, wpi::units::meters_per_second_t vy,
void Drive(wpi::units::meters_per_second_t vx,
wpi::units::meters_per_second_t vy,
wpi::units::radians_per_second_t omega);
void SetChassisSpeeds(const wpi::math::ChassisSpeeds& targetChassisSpeeds,
bool openLoop, bool steerInPlace);

View File

@@ -44,11 +44,12 @@ class SwerveDriveSim {
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics);
SwerveDriveSim(
const wpi::math::LinearSystem<2, 1, 2>& drivePlant, wpi::units::volt_t driveKs,
const wpi::math::DCMotor& driveMotor, double driveGearing,
wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant, wpi::units::volt_t steerKs,
const wpi::math::DCMotor& steerMotor, double steerGearing,
const wpi::math::LinearSystem<2, 1, 2>& drivePlant,
wpi::units::volt_t driveKs, const wpi::math::DCMotor& driveMotor,
double driveGearing, wpi::units::meter_t driveWheelRadius,
const wpi::math::LinearSystem<2, 1, 2>& steerPlant,
wpi::units::volt_t steerKs, const wpi::math::DCMotor& steerMotor,
double steerGearing,
const wpi::math::SwerveDriveKinematics<numModules>& kinematics);
void SetDriveInputs(const std::array<wpi::units::volt_t, numModules>& inputs);
void SetSteerInputs(const std::array<wpi::units::volt_t, numModules>& inputs);
@@ -75,9 +76,9 @@ class SwerveDriveSim {
std::array<Eigen::Matrix<double, 2, 1>, numModules> GetSteerStates() const;
wpi::units::radians_per_second_t GetOmega() const;
wpi::units::ampere_t GetCurrentDraw(const wpi::math::DCMotor& motor,
wpi::units::radians_per_second_t velocity,
wpi::units::volt_t inputVolts,
wpi::units::volt_t batteryVolts) const;
wpi::units::radians_per_second_t velocity,
wpi::units::volt_t inputVolts,
wpi::units::volt_t batteryVolts) const;
std::array<wpi::units::ampere_t, numModules> GetDriveCurrentDraw() const;
std::array<wpi::units::ampere_t, numModules> GetSteerCurrentDraw() const;
wpi::units::ampere_t GetTotalCurrentDraw() const;

View File

@@ -4,8 +4,8 @@ plugins {
}
java {
sourceCompatibility = JavaVersion.VERSION_17
targetCompatibility = JavaVersion.VERSION_17
sourceCompatibility = JavaVersion.VERSION_21
targetCompatibility = JavaVersion.VERSION_21
}
def ROBOT_MAIN_CLASS = "frc.robot.Main"
@@ -15,7 +15,7 @@ repositories {
}
wpi.maven.useDevelopment = true
wpi.versions.wpilibVersion = "2027.0.+"
wpi.versions.wpilibVersion = "2027.0.0-alpha-4"
// Define my targets (SystemCore) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.

View File

@@ -1,6 +1,6 @@
distributionBase=GRADLE_USER_HOME
distributionPath=permwrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-9.2.0-bin.zip
networkTimeout=10000
validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME

Some files were not shown because too many files have changed in this diff Show More