Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Bump wpilib to latest dev #1327

Merged
merged 5 commits into from
May 26, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ jobs:
- run: git fetch --tags --force
- run: |
chmod +x gradlew
./gradlew photon-lib:build --max-workers 1
./gradlew photon-targeting:build photon-lib:build --max-workers 1
- run: ./gradlew photon-lib:publish photon-targeting:publish
name: Publish
env:
Expand Down Expand Up @@ -180,7 +180,7 @@ jobs:
- name: Build PhotonLib
run: |
chmod +x gradlew
./gradlew photon-lib:build --max-workers 1
./gradlew photon-targeting:build photon-lib:build --max-workers 1
- name: Publish
run: |
chmod +x gradlew
Expand Down
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ allprojects {
apply from: "versioningHelper.gradle"

ext {
wpilibVersion = "2024.3.2"
wpilibVersion = "2024.3.2-139-gfbfef85"
wpimathVersion = wpilibVersion
openCVversion = "4.8.0-2"
joglVersion = "2.4.0-rc-20200307"
Expand Down
207 changes: 207 additions & 0 deletions photon-core/src/main/java/edu/wpi/first/util/RuntimeDetector.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,207 @@
/*
* Copyright (C) Photon Vision.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/

package edu.wpi.first.util;

import java.io.File;

/**
* A utility class for detecting and providing platform-specific such as OS and CPU architecture.
*/
public final class RuntimeDetector {
private static String filePrefix;
private static String fileExtension;
private static String filePath;

private static synchronized void computePlatform() {
if (fileExtension != null && filePath != null && filePrefix != null) {
return;
}

boolean intel32 = is32BitIntel();
boolean intel64 = is64BitIntel();
boolean arm64 = isArm64();

if (isWindows()) {
filePrefix = "";
fileExtension = ".dll";
if (intel32) {
filePath = "/windows/x86/";
} else {
filePath = "/windows/x86-64/";
}
} else if (isMac()) {
filePrefix = "lib";
fileExtension = ".dylib";
filePath = "/osx/universal/";
} else if (isLinux()) {
filePrefix = "lib";
fileExtension = ".so";
if (intel32) {
filePath = "/linux/x86/";
} else if (intel64) {
filePath = "/linux/x86-64/";
} else if (isAthena()) {
filePath = "/linux/athena/";
} else if (isArm32()) {
filePath = "/linux/arm32/";
} else if (arm64) {
filePath = "/linux/arm64/";
} else {
filePath = "/linux/nativearm/";
}
} else {
throw new IllegalStateException("Failed to determine OS");
}
}

/**
* Get the file prefix for the current system.
*
* @return The file prefix.
*/
public static synchronized String getFilePrefix() {
computePlatform();

return filePrefix;
}

/**
* Get the file extension for the current system.
*
* @return The file extension.
*/
public static synchronized String getFileExtension() {
computePlatform();

return fileExtension;
}

/**
* Get the platform path for the current system.
*
* @return The platform path.
*/
public static synchronized String getPlatformPath() {
computePlatform();

return filePath;
}

/**
* Get the path to the requested resource.
*
* @param libName Library name.
* @return The path to the requested resource.
*/
public static synchronized String getLibraryResource(String libName) {
computePlatform();

return filePath + filePrefix + libName + fileExtension;
}

/**
* Get the path to the hash to the requested resource.
*
* @param libName Library name.
* @return The path to the hash to the requested resource.
*/
public static synchronized String getHashLibraryResource(String libName) {
computePlatform();

return filePath + libName + ".hash";
}

/**
* Check if hardware platform is Athena.
*
* @return True if hardware platform is Athena.
*/
public static boolean isAthena() {
File runRobotFile = new File("/usr/local/frc/bin/frcRunRobot.sh");
return runRobotFile.exists();
}

/**
* Check if OS is Arm32.
*
* @return True if OS is Arm32.
*/
public static boolean isArm32() {
String arch = System.getProperty("os.arch");
return "arm".equals(arch) || "arm32".equals(arch);
}

/**
* Check if architecture is Arm64.
*
* @return if architecture is Arm64.
*/
public static boolean isArm64() {
String arch = System.getProperty("os.arch");
return "aarch64".equals(arch) || "arm64".equals(arch);
}

/**
* Check if OS is Linux.
*
* @return if OS is Linux.
*/
public static boolean isLinux() {
return System.getProperty("os.name").startsWith("Linux");
}

/**
* Check if OS is Windows.
*
* @return if OS is Windows.
*/
public static boolean isWindows() {
return System.getProperty("os.name").startsWith("Windows");
}

/**
* Check if OS is Mac.
*
* @return if OS is Mac.
*/
public static boolean isMac() {
return System.getProperty("os.name").startsWith("Mac");
}

/**
* Check if OS is 32bit Intel.
*
* @return if OS is 32bit Intel.
*/
public static boolean is32BitIntel() {
String arch = System.getProperty("os.arch");
return "x86".equals(arch) || "i386".equals(arch);
}

/**
* Check if OS is 64bit Intel.
*
* @return if OS is 64bit Intel.
*/
public static boolean is64BitIntel() {
String arch = System.getProperty("os.arch");
return "amd64".equals(arch) || "x86_64".equals(arch);
}

private RuntimeDetector() {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,7 @@ public void load() {
if (atfl == null) {
logger.info("Loading default apriltags for 2024 field...");
try {
atfl = AprilTagFields.kDefaultField.loadAprilTagLayoutField();
atfl = AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
} catch (UncheckedIOException e) {
logger.error("Error loading WPILib field", e);
atfl = null;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -294,7 +294,7 @@ public void load() {
} catch (IOException e) {
logger.error("Could not deserialize apriltag layout! Loading defaults");
try {
atfl = AprilTagFields.kDefaultField.loadAprilTagLayoutField();
atfl = AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);
} catch (UncheckedIOException e2) {
logger.error("Error loading WPILib field", e);
atfl = null;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@

import com.fasterxml.jackson.databind.ObjectMapper;
import edu.wpi.first.apriltag.jni.AprilTagJNI;
import edu.wpi.first.cscore.CameraServerCvJNI;
import edu.wpi.first.cscore.CameraServerJNI;
import edu.wpi.first.cscore.OpenCvLoader;
import edu.wpi.first.hal.JNIWrapper;
import edu.wpi.first.math.WPIMathJNI;
import edu.wpi.first.math.geometry.Translation2d;
Expand Down Expand Up @@ -48,7 +48,7 @@ public static boolean loadLibraries() {
WPIUtilJNI.Helper.setExtractOnStaticLoad(false);
WPIMathJNI.Helper.setExtractOnStaticLoad(false);
CameraServerJNI.Helper.setExtractOnStaticLoad(false);
CameraServerCvJNI.Helper.setExtractOnStaticLoad(false);
OpenCvLoader.Helper.setExtractOnStaticLoad(false);
JNIWrapper.Helper.setExtractOnStaticLoad(false);
WPINetJNI.Helper.setExtractOnStaticLoad(false);
AprilTagJNI.Helper.setExtractOnStaticLoad(false);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -440,7 +440,7 @@ class PhotonCameraSim {
double minTargetAreaPercent;

frc::AprilTagFieldLayout tagLayout{
frc::LoadAprilTagLayoutField(frc::AprilTagField::k2024Crescendo)};
frc::AprilTagFieldLayout::LoadField(frc::AprilTagField::k2024Crescendo)};

cs::CvSource videoSimRaw;
cv::Mat videoSimFrameRaw{};
Expand Down
4 changes: 2 additions & 2 deletions photon-lib/src/test/java/org/photonvision/OpenCVTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@

import static org.junit.jupiter.api.Assertions.*;

import edu.wpi.first.cscore.CameraServerCvJNI;
import edu.wpi.first.cscore.OpenCvLoader;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
Expand Down Expand Up @@ -77,7 +77,7 @@ public static void assertSame(Transform3d trf1, Transform3d trf2) {

@BeforeAll
public static void setUp() throws IOException {
CameraServerCvJNI.forceLoad();
OpenCvLoader.forceLoad();

// NT live for debug purposes
NetworkTableInstance.getDefault().startServer();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,10 @@
#pragma once

#include <algorithm>
#include <bit>
#include <string>
#include <vector>

#include <wpi/Endian.h>

namespace photon {

/**
Expand Down Expand Up @@ -73,8 +72,7 @@ class Packet {
packetData.resize(packetData.size() + sizeof(T));
std::memcpy(packetData.data() + writePos, &src, sizeof(T));

if constexpr (wpi::support::endian::system_endianness() ==
wpi::support::endianness::little) {
if constexpr (std::endian::native == std::endian::little) {
// Reverse to big endian for network conventions.
std::reverse(packetData.data() + writePos,
packetData.data() + writePos + sizeof(T));
Expand All @@ -95,8 +93,7 @@ class Packet {
if (!packetData.empty()) {
std::memcpy(&value, packetData.data() + readPos, sizeof(T));

if constexpr (wpi::support::endian::system_endianness() ==
wpi::support::endianness::little) {
if constexpr (std::endian::native == std::endian::little) {
// Reverse to little endian for host.
uint8_t& raw = reinterpret_cast<uint8_t&>(value);
std::reverse(&raw, &raw + sizeof(T));
Expand Down
14 changes: 14 additions & 0 deletions photon-targeting/src/test/java/org/photonvision/PacketTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,8 @@ void trackedTargetSerde() {
9.0,
-5.0,
-1,
-1,
-1f,
new Transform3d(),
new Transform3d(),
-1,
Expand Down Expand Up @@ -198,6 +200,8 @@ void pipelineResultSerde() {
9.0,
4.0,
2,
-1,
-1f,
new Transform3d(new Translation3d(1, 2, 3), new Rotation3d(1, 2, 3)),
new Transform3d(new Translation3d(1, 2, 3), new Rotation3d(1, 2, 3)),
0.25,
Expand All @@ -217,6 +221,8 @@ void pipelineResultSerde() {
9.1,
6.7,
3,
-1,
-1f,
new Transform3d(new Translation3d(4, 2, 3), new Rotation3d(1, 5, 3)),
new Transform3d(new Translation3d(4, 2, 3), new Rotation3d(1, 5, 3)),
0.25,
Expand Down Expand Up @@ -247,6 +253,8 @@ void pipelineResultSerde() {
9.0,
4.0,
2,
-1,
-1f,
new Transform3d(new Translation3d(1, 2, 3), new Rotation3d(1, 2, 3)),
new Transform3d(new Translation3d(1, 2, 3), new Rotation3d(1, 2, 3)),
0.25,
Expand All @@ -266,6 +274,8 @@ void pipelineResultSerde() {
9.1,
6.7,
3,
-1,
-1f,
new Transform3d(new Translation3d(4, 2, 3), new Rotation3d(1, 5, 3)),
new Transform3d(new Translation3d(4, 2, 3), new Rotation3d(1, 5, 3)),
0.25,
Expand Down Expand Up @@ -303,6 +313,8 @@ public void testMultiTargetSerde() {
9.0,
4.0,
2,
-1,
-1f,
new Transform3d(new Translation3d(1, 2, 3), new Rotation3d(1, 2, 3)),
new Transform3d(new Translation3d(1, 2, 3), new Rotation3d(1, 2, 3)),
0.25,
Expand All @@ -322,6 +334,8 @@ public void testMultiTargetSerde() {
9.1,
6.7,
3,
-1,
-1f,
new Transform3d(new Translation3d(4, 2, 3), new Rotation3d(1, 5, 3)),
new Transform3d(new Translation3d(4, 2, 3), new Rotation3d(1, 5, 3)),
0.25,
Expand Down
Loading
Loading