diff --git a/.gitignore b/.gitignore index 58cbda7..64ebc84 100644 --- a/.gitignore +++ b/.gitignore @@ -202,4 +202,7 @@ src/backend/generated/ target/ *.pyc -src/main/deploy/config \ No newline at end of file +src/main/deploy/config + +*.db +.coverage \ No newline at end of file diff --git a/Makefile b/Makefile index da2c96e..c3b689a 100644 --- a/Makefile +++ b/Makefile @@ -14,12 +14,13 @@ THRIFT_GEN_DIR = $(GEN_DIR)/thrift THRIFT_TS_SCHEMA_GEN_DIR = $(THRIFT_GEN_DIR)/ts_schema PROTO_PY_GEN_DIR = $(PROTO_GEN_DIR)/python -prep-project: - if [ ! -d ".venv" ]; then \ - python3 -m venv .venv; \ - fi - +initialize: + python3 -m venv .venv .venv/bin/pip install -r requirements.txt + make test + +test: + PYTHONPATH=src pytest generate-proto-python: mkdir -p $(PROTO_PY_GEN_DIR) diff --git a/build.gradle b/build.gradle index ca5a2ee..f7da963 100644 --- a/build.gradle +++ b/build.gradle @@ -220,20 +220,6 @@ def applyBackend(expectedNumOfPis) { } } -def installPythonDependencies() { - project.exec { - commandLine "make", "prep-project" - } -} - -tasks.register("installPythonDependencies") { - group = "build" - description = "Install Python dependencies" - doLast { - installPythonDependencies() - } -} - buildDynamically("./config.ini") tasks.register("applyBackend") { @@ -252,7 +238,6 @@ tasks.register("generateConfig") { } } -tasks.build.dependsOn(tasks.installPythonDependencies) tasks.build.dependsOn(tasks.generateConfig) tasks.build.dependsOn(tasks.generateProto) diff --git a/docs/HowToInitialize.md b/docs/HowToInitialize.md index 756991b..ce1ba87 100644 --- a/docs/HowToInitialize.md +++ b/docs/HowToInitialize.md @@ -150,13 +150,6 @@ make --version # Setting Up Workspace -## Clone the repository - -```bash -git clone https://github.com/PinewoodRobotics/command-robot-base.git -cd command-robot-base -``` - ## Initialize the submodules ```bash diff --git a/pytest.ini b/pytest.ini new file mode 100644 index 0000000..5d14d0d --- /dev/null +++ b/pytest.ini @@ -0,0 +1,10 @@ +[pytest] +pythonpath = src +testpaths = src/backend/python +addopts = + --cov=backend.python.april + --cov=backend.python.pos_extrapolator + --cov=backend.python.common + --cov-report=term-missing +norecursedirs = + lib/ \ No newline at end of file diff --git a/requirements.txt b/requirements.txt index 37e6cc3..cbc9cfc 100644 --- a/requirements.txt +++ b/requirements.txt @@ -24,4 +24,7 @@ zeroconf thrift opencv-python requests -ultralytics \ No newline at end of file +ultralytics + +# dev deps +pytest-cov \ No newline at end of file diff --git a/src/backend/deployment/util.py b/src/backend/deployment/util.py index 852273a..714906a 100644 --- a/src/backend/deployment/util.py +++ b/src/backend/deployment/util.py @@ -138,10 +138,12 @@ def _deploy_backend_to_pi( "-p", pi.password, "ssh", + "-o", + "StrictHostKeyChecking=no", "-p", str(getattr(pi, "port", 22)), f"ubuntu@{pi.address}", - f"sudo mkdir -p {remote_target_dir}", + f"mkdir -p {remote_target_dir}", ] mkdir_proc = subprocess.run(mkdir_cmd) @@ -248,10 +250,6 @@ def _deploy_compilable(pi: _RaspberryPi, modules: list[_Module]): from backend.deployment.compilation.cpp.cpp import CPlusPlus from backend.deployment.compilation.rust.rust import Rust - if os.path.exists(LOCAL_BINARIES_PATH): - shutil.rmtree(LOCAL_BINARIES_PATH) - os.makedirs(LOCAL_BINARIES_PATH, exist_ok=True) - if SHOULD_REBUILD_BINARIES: for module in modules: if not isinstance(module, _CompilableModule): @@ -350,7 +348,7 @@ class RustModule(_CompilableModule, _RunnableModule): def get_run_command(self) -> str: extra_run_args = self.get_extra_run_args() - return f"{LOCAL_BINARIES_PATH}/{get_self_ldd_version()}/{get_self_architecture()}/{self.runnable_name} {extra_run_args}".strip() + return f"{LOCAL_BINARIES_PATH}/{get_self_ldd_version()}/{get_self_architecture()}/rust/{self.runnable_name}/{self.runnable_name} {extra_run_args}".strip() @dataclass class ProtobufModule(_CompilableModule): @@ -403,6 +401,10 @@ def with_preset_pi_addresses( def with_automatic_discovery( modules: list[_Module], backend_local_path: str = "src/backend/" ): + if os.path.exists(LOCAL_BINARIES_PATH): + shutil.rmtree(LOCAL_BINARIES_PATH) + os.makedirs(LOCAL_BINARIES_PATH, exist_ok=True) + raspberrypis = _RaspberryPi.discover_all() DeploymentOptions.with_preset_pi_addresses( raspberrypis, modules, backend_local_path diff --git a/src/backend/python/common/__tests__/test_all.py b/src/backend/python/common/__tests__/test_all.py deleted file mode 100644 index 02655f9..0000000 --- a/src/backend/python/common/__tests__/test_all.py +++ /dev/null @@ -1,10 +0,0 @@ -import backend.python.pos_extrapolator.main -import backend.python.april.src.main -import backend.python.common.config -import backend.python.common.util -import backend.python.common.camera -import backend.python.common.debug - - -def test_all(): - pass diff --git a/src/backend/python/common/__tests__/test_system.py b/src/backend/python/common/__tests__/test_system.py index 740efd0..809bf59 100644 --- a/src/backend/python/common/__tests__/test_system.py +++ b/src/backend/python/common/__tests__/test_system.py @@ -1,5 +1 @@ from backend.python.common.util.system import get_local_hostname - - -def test_get_local_hostname(): - assert get_local_hostname() == "Deniss-MacBook-Pro.local" diff --git a/src/backend/python/common/camera/abstract_camera.py b/src/backend/python/common/camera/abstract_camera.py index 0b4203f..0cfc2de 100644 --- a/src/backend/python/common/camera/abstract_camera.py +++ b/src/backend/python/common/camera/abstract_camera.py @@ -48,12 +48,6 @@ def __init__( exposure_time: float = -1, brightness: int | None = None, ) -> None: - if isinstance(camera_port, str): - try: - camera_port: int = int(camera_port) - except ValueError: - pass - self.port: int | str = camera_port self.camera_name: str = camera_name self.width: int = width diff --git a/src/backend/python/common/camera/image_utils.py b/src/backend/python/common/camera/image_utils.py index e6aa3e5..37eb3ac 100644 --- a/src/backend/python/common/camera/image_utils.py +++ b/src/backend/python/common/camera/image_utils.py @@ -1,15 +1,17 @@ import time from logging import info +from typing import cast import cv2 +from cv2.typing import MatLike import numpy as np -from backend.python.common.debug.logger import stats_for_nerds from backend.generated.proto.python.sensor.camera_sensor_pb2 import ( ImageCompression, ImageData, ImageFormat, ) +from backend.python.common.debug.logger import stats_for_nerds def from_proto_format(format: ImageFormat) -> int: @@ -58,10 +60,15 @@ def compress_image( def decode_image(proto_image: ImageData) -> np.ndarray: channels = from_proto_format_to_n_channels(proto_image.format) if proto_image.compression == ImageCompression.JPEG: - return cv2.imdecode( - np.frombuffer(proto_image.image, dtype=np.uint8), + decoded = cv2.imdecode( + cast(MatLike, np.frombuffer(proto_image.image, dtype=np.uint8)), from_proto_format(proto_image.format), ) + if decoded is None: + raise ValueError( + f"Failed to decode JPEG image (format={proto_image.format}, bytes={len(proto_image.image)})" + ) + return cast(np.ndarray, decoded) else: return np.frombuffer(proto_image.image, dtype=np.uint8).reshape( (proto_image.height, proto_image.width, channels) diff --git a/src/backend/python/common/debug/logger.py b/src/backend/python/common/debug/logger.py index f2651bf..840d378 100644 --- a/src/backend/python/common/debug/logger.py +++ b/src/backend/python/common/debug/logger.py @@ -87,28 +87,6 @@ def wrapper(*args, **kwargs): return decorator -def stats_for_nerds_akit(send_stats: bool = True, print_stats: bool = True): - def decorator(func): - @wraps(func) - def wrapper(*args, **kwargs): - start_time = time.time() - result = func(*args, **kwargs) - end_time = time.time() - if send_stats: - log_to_akit(func.__name__, [(end_time - start_time) * 1000]) - - if print_stats: - info( - f"Function {func.__name__} took {(end_time - start_time) * 1000}ms to run." - ) - - return result - - return wrapper - - return decorator - - def init_logging( prefix: str, log_level: LogLevel, diff --git a/src/config/april_tags_detection/index.ts b/src/config/april_tags_detection/index.ts index 14db141..76c9147 100644 --- a/src/config/april_tags_detection/index.ts +++ b/src/config/april_tags_detection/index.ts @@ -17,14 +17,10 @@ export const april_tag_detection_config: AprilDetectionConfig = { send_stats: true, stats_topic: "apriltag/stats", pi_name_to_special_detector_config: { - // this section is for special detectors. This means that if you want to use a non-standard detector, say GPU based - // that only works on a specific Pi, you can add it here with the Pi name as the key. - /* jetson1: { type: SpecialDetectorType.GPU_CUDA, py_lib_searchpath: "/opt/blitz/B.L.I.T.Z/build/release/2.35/aarch64/cpp/cuda-tags-lib/", }, - */ }, }; diff --git a/src/config/cameras/front_left.ts b/src/config/cameras/front_left.ts new file mode 100644 index 0000000..3a622bb --- /dev/null +++ b/src/config/cameras/front_left.ts @@ -0,0 +1,35 @@ +import { + CameraParameters, + CameraType, +} from "generated/thrift/gen-nodejs/camera_types"; +import { MatrixUtil, VectorUtil } from "../util/math"; + +const front_left: CameraParameters = { + pi_to_run_on: "tynan", + name: "front_left", + camera_path: "/dev/usb_cam4", + flags: 0, + width: 800, + height: 600, + max_fps: 100, + camera_matrix: MatrixUtil.buildMatrix([ + [685.088010528533, 0.0, 400.456913426101], + [0.0, 685.286311116306, 283.611674040712], + [0.0, 0.0, 1.0], + ]), + dist_coeff: VectorUtil.fromArray([ + 0.0370949377097917, 0.041319913100527, -0.00128168607814328, + -0.00128042296949747, -0.298591139932664, + ]), + exposure_time: 10, + camera_type: CameraType.OV2311, + video_options: { + send_feed: true, + compression_quality: 50, + publication_topic: "cameras/front_left", + do_compression: true, + overlay_tags: true, + }, +}; + +export default front_left; diff --git a/src/config/cameras/front_right.ts b/src/config/cameras/front_right.ts new file mode 100644 index 0000000..058d8b0 --- /dev/null +++ b/src/config/cameras/front_right.ts @@ -0,0 +1,34 @@ +import { + CameraParameters, + CameraType, +} from "generated/thrift/gen-nodejs/camera_types"; +import { MatrixUtil, VectorUtil } from "../util/math"; + +const front_right: CameraParameters = { + pi_to_run_on: "tynan", + name: "front_right", + camera_path: "/dev/usb_cam2", + flags: 0, + width: 800, + height: 600, + max_fps: 100, + camera_matrix: MatrixUtil.buildMatrix([ + [685.1818937239501, 0.0, 414.2897986078692], + [0.0, 685.3366953090806, 307.27153822775506], + [0.0, 0.0, 1.0], + ]), + dist_coeff: VectorUtil.fromArray([ + 0.03841168751857183, -0.03836398867353221, 0.00011911539228647425, + -0.00047135490659979865, -0.011145047269650642, + ]), + exposure_time: 10, + camera_type: CameraType.OV2311, + video_options: { + send_feed: false, + do_compression: true, + overlay_tags: false, + compression_quality: 30, + }, +}; + +export default front_right; diff --git a/src/config/cameras/jetson_cam.ts b/src/config/cameras/jetson_cam.ts new file mode 100644 index 0000000..331a89f --- /dev/null +++ b/src/config/cameras/jetson_cam.ts @@ -0,0 +1,35 @@ +import { + CameraParameters, + CameraType, +} from "generated/thrift/gen-nodejs/camera_types"; +import { MatrixUtil, VectorUtil } from "../util/math"; + +const jetson_cam: CameraParameters = { + pi_to_run_on: "jetson1", + name: "jetson_cam", + camera_path: "/dev/video0", + flags: 0, + width: 640, + height: 480, + max_fps: 60, + camera_matrix: MatrixUtil.buildMatrix([ + [685.088010528533, 0.0, 400.456913426101], + [0.0, 685.286311116306, 283.611674040712], + [0.0, 0.0, 1.0], + ]), + dist_coeff: VectorUtil.fromArray([ + 0.0370949377097917, 0.041319913100527, -0.00128168607814328, + -0.00128042296949747, -0.298591139932664, + ]), + exposure_time: 10, + camera_type: 0 as CameraType, + video_options: { + send_feed: true, + publication_topic: "camera/jetson/video", + compression_quality: 90, + do_compression: false, + overlay_tags: false, + }, +}; + +export default jetson_cam; diff --git a/src/config/cameras/logitech_cam.ts b/src/config/cameras/logitech_cam.ts index f058ad0..f688835 100644 --- a/src/config/cameras/logitech_cam.ts +++ b/src/config/cameras/logitech_cam.ts @@ -5,9 +5,9 @@ import { import { MatrixUtil, VectorUtil } from "../util/math"; const logitech_cam: CameraParameters = { - pi_to_run_on: "jetson1", + pi_to_run_on: "nathan-hale", name: "front_left", - camera_path: "/dev/video0", + camera_path: "/dev/usb_cam2", flags: 0, width: 640, height: 480, @@ -21,14 +21,14 @@ const logitech_cam: CameraParameters = { -0.44180630590282977, 0.23535469092748917, -0.0020750769021071484, -7.455571357241929e-5, -0.08061071367847858, ]), - exposure_time: 150, + exposure_time: 400, camera_type: CameraType.ULTRAWIDE_100, - brightness: 200, + brightness: 50, video_options: { - send_feed: false, - overlay_tags: true, + send_feed: true, + overlay_tags: false, publication_topic: "camera/logitech/video", - compression_quality: 30, + compression_quality: 90, do_compression: true, }, }; diff --git a/src/config/cameras/prod_1.ts b/src/config/cameras/prod_1.ts new file mode 100644 index 0000000..c0f106f --- /dev/null +++ b/src/config/cameras/prod_1.ts @@ -0,0 +1,28 @@ +import { + CameraType, + type CameraParameters, +} from "generated/thrift/gen-nodejs/camera_types"; +import { MatrixUtil, VectorUtil } from "../util/math"; + +const prod1: CameraParameters = { + pi_to_run_on: "tripoli", + name: "one", + camera_path: "/dev/video0", + flags: 0, + width: 800, + height: 600, + max_fps: 100, + camera_matrix: MatrixUtil.buildMatrix([ + [454.7917491985464, 0.0, 405.6029022992675], + [0.0, 454.729749644609, 321.75698981738134], + [0.0, 0.0, 1.0], + ]), + dist_coeff: VectorUtil.fromArray([ + 0.04216332435519303, -0.06145045363038189, 5.072789006860842e-6, + -0.0002106044632593869, 0.004071613340637429, + ]), + exposure_time: 8, + camera_type: CameraType.OV2311, +}; + +export default prod1; diff --git a/src/config/cameras/rear_left.ts b/src/config/cameras/rear_left.ts new file mode 100644 index 0000000..2e4bba4 --- /dev/null +++ b/src/config/cameras/rear_left.ts @@ -0,0 +1,36 @@ +import { + CameraType, + type CameraParameters, +} from "generated/thrift/gen-nodejs/camera_types"; +import { MatrixUtil, VectorUtil } from "../util/math"; + +const rear_left: CameraParameters = { + pi_to_run_on: "nathan-hale", + name: "rear_left", + camera_path: "/dev/usb_cam1", + flags: 0, + width: 800, + height: 600, + max_fps: 100, + camera_matrix: MatrixUtil.buildMatrix([ + // front left camera calib + [685.088010528533, 0.0, 400.456913426101], + [0.0, 685.286311116306, 283.611674040712], + [0.0, 0.0, 1.0], + ]), + dist_coeff: VectorUtil.fromArray([ + 0.0370949377097917, 0.041319913100527, -0.00128168607814328, + -0.00128042296949747, -0.298591139932664, + ]), + exposure_time: 10, + camera_type: CameraType.OV2311, + video_options: { + send_feed: false, + overlay_tags: true, + publication_topic: "camera/rear_left/video", + compression_quality: 30, + do_compression: true, + }, +}; + +export default rear_left; diff --git a/src/config/cameras/rear_right.ts b/src/config/cameras/rear_right.ts new file mode 100644 index 0000000..7691f36 --- /dev/null +++ b/src/config/cameras/rear_right.ts @@ -0,0 +1,33 @@ +import { + CameraType, + type CameraParameters, +} from "generated/thrift/gen-nodejs/camera_types"; +import { MatrixUtil, VectorUtil } from "../util/math"; + +const rear_right: CameraParameters = { + pi_to_run_on: "nathan-hale", + name: "rear_right", + camera_path: "/dev/usb_cam3", + flags: 0, + width: 800, + height: 600, + max_fps: 100, + camera_matrix: MatrixUtil.buildMatrix([ + // front left camera calib + [685.088010528533, 0.0, 400.456913426101], + [0.0, 685.286311116306, 283.611674040712], + [0.0, 0.0, 1.0], + ]), + dist_coeff: VectorUtil.fromArray([ + 0.0370949377097917, 0.041319913100527, -0.00128168607814328, + -0.00128042296949747, -0.298591139932664, + ]), + exposure_time: 10, + camera_type: CameraType.OV2311, + video_options: { + send_feed: false, + overlay_tags: false, + }, +}; + +export default rear_right; diff --git a/src/config/index.ts b/src/config/index.ts index e50a799..647cfc6 100644 --- a/src/config/index.ts +++ b/src/config/index.ts @@ -1,13 +1,19 @@ import type { Config } from "generated/thrift/gen-nodejs/config_types"; import { april_tag_detection_config } from "./april_tags_detection"; +import prod1 from "./cameras/prod_1"; import lidar_configs from "./lidar"; import pathfinding_config from "./pathfinding"; import { pose_extrapolator } from "./pos_extrapolator"; +import front_left from "./cameras/front_left"; +import front_right from "./cameras/front_right"; +import rear_left from "./cameras/rear_left"; +import rear_right from "./cameras/rear_right"; +import jetson_cam from "./cameras/jetson_cam"; import logitech_cam from "./cameras/logitech_cam"; const config: Config = { pos_extrapolator: pose_extrapolator, - cameras: [logitech_cam], + cameras: [front_left, front_right, rear_left, rear_right], april_detection: april_tag_detection_config, lidar_configs: lidar_configs, pathfinding: pathfinding_config, diff --git a/src/config/lidar/index.ts b/src/config/lidar/index.ts index 155f5de..54e47ad 100644 --- a/src/config/lidar/index.ts +++ b/src/config/lidar/index.ts @@ -5,7 +5,7 @@ const lidar_configs: { [k: string]: LidarConfig; } = { "lidar-1": { - pi_to_run_on: "jetson1", + pi_to_run_on: "tripli", port: "/dev/ttyUSB0", baudrate: 2000000, is_2d: false, diff --git a/src/config/pathfinding/index.ts b/src/config/pathfinding/index.ts index 741145f..a323d72 100644 --- a/src/config/pathfinding/index.ts +++ b/src/config/pathfinding/index.ts @@ -6,7 +6,7 @@ const pathfinding_config: PathfindingConfig = { lidar_config: { use_lidar: true, lidar_voxel_size_meters: 0.1, - lidar_pub_topic: "lidar_points", + lidar_pub_topic: "lidar/lidar3d/pointcloud/3d/robotframe", unit_conversion: { non_unit_to_unit: 1, unit_to_non_unit: 1, @@ -21,6 +21,7 @@ const pathfinding_config: PathfindingConfig = { }, publish_map: true, map_pub_topic: "pathfinding_map", + global_pose_pub_topic: "pos-extrapolator/robot-position", x_map_to_meters: { non_unit_to_unit: 5.698006, // px/m unit_to_non_unit: 0.1755, // m/px diff --git a/src/config/pos_extrapolator/april_tag_det_config/index.ts b/src/config/pos_extrapolator/april_tag_det_config/index.ts index 8891b27..2094896 100644 --- a/src/config/pos_extrapolator/april_tag_det_config/index.ts +++ b/src/config/pos_extrapolator/april_tag_det_config/index.ts @@ -1,6 +1,6 @@ import { AprilTagConfig, - TagDistanceDiscardMode, + TagDisambiguationMode, TagUseImuRotation, } from "generated/thrift/gen-nodejs/pos_extrapolator_types"; import { reefscape_field } from "../tag_config/reefscape"; @@ -8,7 +8,6 @@ import { MatrixUtil, VectorUtil } from "../../util/math"; const april_tag_pos_config: AprilTagConfig = { tag_position_config: reefscape_field, - tag_discard_mode: TagDistanceDiscardMode.ADD_WEIGHT, camera_position_config: { front_left: { position: VectorUtil.fromArray([0.33, 0.33, 0.0]), @@ -28,12 +27,8 @@ const april_tag_pos_config: AprilTagConfig = { }, }, tag_use_imu_rotation: TagUseImuRotation.NEVER, - discard_config: { - distance_threshold: 4, - angle_threshold_degrees: 10, - weight_per_m_from_discard_distance: 2, - weight_per_degree_from_discard_angle: 0.5, - }, + disambiguation_time_window_s: 0.05, + tag_disambiguation_mode: TagDisambiguationMode.LEAST_ANGLE_AND_DISTANCE, }; export default april_tag_pos_config; diff --git a/src/config/pos_extrapolator/kalman_filter_config/index.ts b/src/config/pos_extrapolator/kalman_filter_config/index.ts index 109c09b..0715e72 100644 --- a/src/config/pos_extrapolator/kalman_filter_config/index.ts +++ b/src/config/pos_extrapolator/kalman_filter_config/index.ts @@ -5,7 +5,7 @@ import { import { MatrixUtil, VectorUtil } from "../../util/math"; export const kalman_filter: KalmanFilterConfig = { - state_vector: VectorUtil.fromArray([0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0]), // [x, y, vx, vy, cos, sin, angular_velocity_rad_s] + state_vector: VectorUtil.fromArray([2.0, 5.0, 0.0, 0.0, 1.0, 0.0, 0.0]), // [x, y, vx, vy, cos, sin, angular_velocity_rad_s] time_step_initial: 0.1, state_transition_matrix: MatrixUtil.buildMatrixFromDiagonal([ 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index b6567f0..fc0d3d1 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -14,34 +14,26 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler; import frc.robot.constant.PiConstants; import frc.robot.constant.TopicConstants; -import frc.robot.util.OptionalAutobahn; import frc.robot.util.RPC; import lombok.Getter; +import pwrup.frc.core.online.raspberrypi.OptionalAutobahn; import pwrup.frc.core.online.raspberrypi.PrintPiLogs; public class Robot extends LoggedRobot { - @Getter // created the "getCommunicationClient" + @Getter private final OptionalAutobahn communicationClient = new OptionalAutobahn(); - @Getter // created the "getOnlineStatus" + @Getter private boolean onlineStatus; private RobotContainer m_robotContainer; public Robot() { - // Start advantage kit logging. This is required for the robot to log data to - // the dashboard. Logger.addDataReceiver(new NT4Publisher()); - // Actually start the logger. This is a pattern where you first set the data - // receivers, then start the logger. Logger.start(); - RPC.SetClient(communicationClient); // set the communication client to the RPC service. - // after this, you should be able to use the RPC service to call methods on the - // backend. See the RPC class for more details. + RPC.SetClient(communicationClient); PrintPiLogs.ToSystemOut(communicationClient, TopicConstants.kPiTechnicalLogTopic); - // print the pi technical log to the system out. otherwise there will not be any - // logs printed to the dashboard. } @Override @@ -54,7 +46,6 @@ public void robotInit() { public void robotPeriodic() { CommandScheduler.getInstance().run(); - // Expose Autobahn connection status to AdvantageKit/NT for visibility. Logger.recordOutput("Autobahn/Connected", communicationClient.isConnected() && onlineStatus); } @@ -94,15 +85,6 @@ public void testInit() { public void testPeriodic() { } - private String readFromFile(File path) { - try { - return Files.readString(Paths.get(path.getAbsolutePath())); - } catch (IOException e) { - e.printStackTrace(); - return null; - } - } - /** * Initializes the network. This is used to connect to the pi network and start * the processes on the pis. @@ -143,4 +125,13 @@ private void initializeNetwork() { } }).start(); } + + private String readFromFile(File path) { + try { + return Files.readString(Paths.get(path.getAbsolutePath())); + } catch (IOException e) { + e.printStackTrace(); + return null; + } + } } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 16a1a8c..694c6d7 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -2,8 +2,21 @@ import edu.wpi.first.wpilibj2.command.Command; +import pwrup.frc.core.controller.FlightModule; +import pwrup.frc.core.controller.FlightStick; +import pwrup.frc.core.controller.LogitechController; +import pwrup.frc.core.controller.OperatorPanel; + public class RobotContainer { + final LogitechController m_controller = new LogitechController(0); + final OperatorPanel m_operatorPanel = new OperatorPanel(1); + final FlightStick m_leftFlightStick = new FlightStick(2); + final FlightStick m_rightFlightStick = new FlightStick(3); + final FlightModule m_flightModule = new FlightModule( + m_leftFlightStick, + m_rightFlightStick); + public RobotContainer() { configureBindings(); } diff --git a/src/main/java/frc/robot/command/task/ExampleCommand.java b/src/main/java/frc/robot/command/task/ExampleCommand.java deleted file mode 100644 index d90579b..0000000 --- a/src/main/java/frc/robot/command/task/ExampleCommand.java +++ /dev/null @@ -1,37 +0,0 @@ -package frc.robot.command.task; - -import edu.wpi.first.wpilibj2.command.Command; - -public class ExampleCommand extends Command { - public ExampleCommand() { - super(); - } - - @Override - public void initialize() { - // initialize the command. This function is called once when the command is - // scheduled - throw new UnsupportedOperationException("Unimplemented method 'initialize'"); - } - - @Override - public void execute() { - // usually you would put the logic of the command here. This function is called - // every 20ms. - throw new UnsupportedOperationException("Unimplemented method 'execute'"); - } - - @Override - public void end(boolean interrupted) { - // end the command. execute stops running after this function is called. - throw new UnsupportedOperationException("Unimplemented method 'end'"); - } - - @Override - public boolean isFinished() { - // this function is called to check if the command is finished. - // if it returns true, the command will be removed from the command scheduler. - // if it returns false, the command will continue to run. - return false; - } -} diff --git a/src/main/java/frc/robot/hardware/AHRSGyro.java b/src/main/java/frc/robot/hardware/AHRSGyro.java new file mode 100644 index 0000000..1f6c48b --- /dev/null +++ b/src/main/java/frc/robot/hardware/AHRSGyro.java @@ -0,0 +1,195 @@ +package frc.robot.hardware; + +import org.littletonrobotics.junction.Logger; + +import com.kauailabs.navx.frc.AHRS; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.I2C; +import frc.robot.util.CustomMath; +import proto.sensor.GeneralSensorDataOuterClass.GeneralSensorData; +import proto.sensor.GeneralSensorDataOuterClass.SensorName; +import proto.sensor.Imu.ImuData; +import proto.util.Position.Position3d; +import proto.util.Vector.Vector3; +import pwrup.frc.core.hardware.sensor.IGyroscopeLike; +import pwrup.frc.core.proto.IDataClass; + +public class AHRSGyro implements IGyroscopeLike, IDataClass { + private static AHRSGyro instance; + private static I2C.Port defaultPort = I2C.Port.kMXP; + + private final AHRS m_gyro; + private double xOffset = 0; + private double yOffset = 0; + private double zOffset = 0; + private double yawSoftOffsetDeg = 0.0; + + public AHRSGyro(I2C.Port i2c_port_id) { + this.m_gyro = new AHRS(i2c_port_id); + m_gyro.reset(); + yawSoftOffsetDeg = 0.0; + } + + /** + * Set the default I2C port used by GetInstance(). + * Call this before the first call to GetInstance(). + */ + public static void setDefaultPort(I2C.Port port) { + defaultPort = port; + } + + public static AHRSGyro GetInstance() { + if (instance == null) { + instance = new AHRSGyro(defaultPort); + } + return instance; + } + + public AHRS getGyro() { + return m_gyro; + } + + @Override + public double[] getYPR() { + double yawAdj = CustomMath.wrapTo180(m_gyro.getYaw() + yawSoftOffsetDeg); + return new double[] { + yawAdj, + m_gyro.getPitch(), + m_gyro.getRoll(), + }; + } + + @Override + public void setPositionAdjustment(double x, double y, double z) { + xOffset = x; + yOffset = y; + zOffset = z; + m_gyro.resetDisplacement(); + } + + @Override + public double[] getLinearAccelerationXYZ() { + return new double[] { + m_gyro.getWorldLinearAccelX(), + m_gyro.getWorldLinearAccelY(), + m_gyro.getWorldLinearAccelZ(), + }; + } + + @Override + public double[] getAngularVelocityXYZ() { + return new double[] { 0, 0, Math.toRadians(m_gyro.getRate()) }; + } + + @Override + public double[] getQuaternion() { + return new double[] { + m_gyro.getQuaternionW(), + m_gyro.getQuaternionX(), + m_gyro.getQuaternionY(), + m_gyro.getQuaternionZ(), + }; + } + + @Override + public double[] getLinearVelocityXYZ() { + return new double[] { + m_gyro.getVelocityX(), + m_gyro.getVelocityY(), + m_gyro.getVelocityZ(), + }; + } + + @Override + public double[] getPoseXYZ() { + return new double[] { + m_gyro.getDisplacementX() + xOffset, + m_gyro.getDisplacementY() + yOffset, + m_gyro.getDisplacementZ() + zOffset, + }; + } + + @Override + public void reset() { + m_gyro.reset(); + yawSoftOffsetDeg = 0.0; + } + + @Override + public void setAngleAdjustment(double angle) { + m_gyro.zeroYaw(); + yawSoftOffsetDeg = -angle; + } + + public void setYawDeg(double targetDeg) { + setAngleAdjustment(targetDeg); + } + + public Rotation2d getNoncontinuousAngle() { + return Rotation2d.fromDegrees(CustomMath.wrapTo180(m_gyro.getAngle())); + } + + @Override + public byte[] getRawConstructedProtoData() { + var poseXYZ = getPoseXYZ(); + var velocityXYZ = getLinearVelocityXYZ(); + var accelerationXYZ = getLinearAccelerationXYZ(); + var yaw = Rotation2d.fromDegrees(getYPR()[0]); + var angularVelocity = getAngularVelocityXYZ(); + + Logger.recordOutput("Imu/AngularVel", angularVelocity[2]); + + Logger.recordOutput("Imu/yaw", yaw.getDegrees()); + + var position = Vector3.newBuilder() + .setX((float) poseXYZ[0]) + .setY((float) poseXYZ[1]) + .setZ((float) poseXYZ[2]) + .build(); + + var direction = Vector3.newBuilder() + .setX((float) yaw.getCos()) + .setY((float) -yaw.getSin()) + .setZ(0) + .build(); + + var position2d = Position3d.newBuilder() + .setPosition(position) + .setDirection(direction) + .build(); + + var velocity = Vector3.newBuilder() + .setX((float) velocityXYZ[0]) + .setY((float) velocityXYZ[1]) + .setZ((float) velocityXYZ[2]) + .build(); + + var acceleration = Vector3.newBuilder() + .setX((float) accelerationXYZ[0]) + .setY((float) accelerationXYZ[1]) + .setZ((float) accelerationXYZ[2]) + .build(); + + var angularVel = Vector3.newBuilder().setX((float) angularVelocity[0]).setY((float) angularVelocity[1]) + .setZ((float) angularVelocity[2]) + .build(); + + var imuData = ImuData.newBuilder() + .setPosition(position2d) + .setVelocity(velocity) + .setAcceleration(acceleration) + .setAngularVelocityXYZ(angularVel) + .build(); + + var all = GeneralSensorData.newBuilder().setImu(imuData).setSensorName(SensorName.IMU).setSensorId("0") + .setTimestamp(System.currentTimeMillis()).setProcessingTimeMs(0); + + return all.build().toByteArray(); + } + + @Override + public String getPublishTopic() { + return "imu/imu"; + } +} diff --git a/src/main/java/frc/robot/hardware/Example.java b/src/main/java/frc/robot/hardware/Example.java deleted file mode 100644 index f291c29..0000000 --- a/src/main/java/frc/robot/hardware/Example.java +++ /dev/null @@ -1,7 +0,0 @@ -package frc.robot.hardware; - -/* import pwrup.frc.core.hardware.sensor.IGyroscopeLike; */ - -// usually you would implement an interface for the hardware you are using. -public class Example /* implements IGyroscopeLike */ { -} diff --git a/src/main/java/frc/robot/hardware/PigeonGyro.java b/src/main/java/frc/robot/hardware/PigeonGyro.java new file mode 100644 index 0000000..6f46af2 --- /dev/null +++ b/src/main/java/frc/robot/hardware/PigeonGyro.java @@ -0,0 +1,201 @@ +package frc.robot.hardware; + +import org.littletonrobotics.junction.Logger; + +import com.ctre.phoenix6.hardware.Pigeon2; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.util.CustomMath; +import proto.sensor.GeneralSensorDataOuterClass.GeneralSensorData; +import proto.sensor.GeneralSensorDataOuterClass.SensorName; +import proto.sensor.Imu.ImuData; +import proto.util.Position.Position3d; +import proto.util.Vector.Vector3; +import pwrup.frc.core.hardware.sensor.IGyroscopeLike; +import pwrup.frc.core.proto.IDataClass; + +public class PigeonGyro extends SubsystemBase implements IGyroscopeLike, IDataClass { + private static PigeonGyro instance; + private static int defaultCanId = 0; + private final Pigeon2 pigeon; + private double xOffset = 0; + private double yOffset = 0; + private double zOffset = 0; + private double yawSoftOffsetDeg = 0.0; + + public PigeonGyro(int canId) { + this.pigeon = new Pigeon2(canId); + pigeon.reset(); + yawSoftOffsetDeg = 0.0; + } + + /** + * Set the default CAN ID used by GetInstance(). + * Call this before the first call to GetInstance(). + */ + public static void setDefaultCanId(int canId) { + defaultCanId = canId; + } + + public static PigeonGyro GetInstance() { + if (instance == null) { + instance = new PigeonGyro(defaultCanId); + } + + return instance; + } + + public Pigeon2 getGyro() { + return pigeon; + } + + @Override + public double[] getYPR() { + double yawAdj = CustomMath.wrapTo180(pigeon.getYaw().getValueAsDouble() + yawSoftOffsetDeg); + return new double[] { + yawAdj, + pigeon.getPitch().getValueAsDouble(), + pigeon.getRoll().getValueAsDouble(), + }; + } + + @Override + public void setPositionAdjustment(double x, double y, double z) { + xOffset = x; + yOffset = y; + zOffset = z; + } + + @Override + public double[] getLinearAccelerationXYZ() { + return new double[] { + pigeon.getAccelerationX().getValueAsDouble(), + pigeon.getAccelerationY().getValueAsDouble(), + pigeon.getAccelerationZ().getValueAsDouble(), + }; + } + + @Override + public double[] getAngularVelocityXYZ() { + return new double[] { + Math.toRadians(pigeon.getAngularVelocityXWorld().getValueAsDouble()), + Math.toRadians(pigeon.getAngularVelocityYWorld().getValueAsDouble()), + Math.toRadians(pigeon.getAngularVelocityZWorld().getValueAsDouble()), + }; + } + + @Override + public double[] getQuaternion() { + return new double[] { + pigeon.getQuatW().getValueAsDouble(), + pigeon.getQuatX().getValueAsDouble(), + pigeon.getQuatY().getValueAsDouble(), + pigeon.getQuatZ().getValueAsDouble(), + }; + } + + @Override + public double[] getLinearVelocityXYZ() { + // Pigeon2 doesn't provide velocity directly, return zeros + return new double[] { 0, 0, 0 }; + } + + @Override + public double[] getPoseXYZ() { + // Pigeon2 doesn't provide displacement directly, return offsets + return new double[] { + xOffset, + yOffset, + zOffset, + }; + } + + @Override + public void reset() { + pigeon.reset(); + yawSoftOffsetDeg = 0.0; + } + + @Override + public void setAngleAdjustment(double angle) { + pigeon.setYaw(0); + yawSoftOffsetDeg = -angle; + } + + public void setYawDeg(double targetDeg) { + setAngleAdjustment(targetDeg); + } + + public Rotation2d getNoncontinuousAngle() { + return Rotation2d.fromDegrees(CustomMath.wrapTo180(pigeon.getYaw().getValueAsDouble())); + } + + @Override + public byte[] getRawConstructedProtoData() { + var poseXYZ = getPoseXYZ(); + var velocityXYZ = getLinearVelocityXYZ(); + var accelerationXYZ = getLinearAccelerationXYZ(); + var yaw = Rotation2d.fromDegrees(getYPR()[0]); + var angularVelocity = getAngularVelocityXYZ(); + + Logger.recordOutput("Imu/AngularVel", angularVelocity[2]); + + Logger.recordOutput("Imu/yaw", yaw.getDegrees()); + + var position = Vector3.newBuilder() + .setX((float) poseXYZ[0]) + .setY((float) poseXYZ[1]) + .setZ((float) poseXYZ[2]) + .build(); + + var direction = Vector3.newBuilder() + .setX((float) yaw.getCos()) + .setY((float) -yaw.getSin()) + .setZ(0) + .build(); + + var position2d = Position3d.newBuilder() + .setPosition(position) + .setDirection(direction) + .build(); + + var velocity = Vector3.newBuilder() + .setX((float) velocityXYZ[0]) + .setY((float) velocityXYZ[1]) + .setZ((float) velocityXYZ[2]) + .build(); + + var acceleration = Vector3.newBuilder() + .setX((float) accelerationXYZ[0]) + .setY((float) accelerationXYZ[1]) + .setZ((float) accelerationXYZ[2]) + .build(); + + var angularVel = Vector3.newBuilder().setX((float) angularVelocity[0]).setY((float) angularVelocity[1]) + .setZ((float) angularVelocity[2]) + .build(); + + var imuData = ImuData.newBuilder() + .setPosition(position2d) + .setVelocity(velocity) + .setAcceleration(acceleration) + .setAngularVelocityXYZ(angularVel) + .build(); + + var all = GeneralSensorData.newBuilder().setImu(imuData).setSensorName(SensorName.IMU).setSensorId("1") + .setTimestamp(System.currentTimeMillis()).setProcessingTimeMs(0); + + return all.build().toByteArray(); + } + + @Override + public String getPublishTopic() { + return "imu/imu"; + } + + @Override + public void periodic() { + Logger.recordOutput("PigeonGyro/yaw", getYPR()[0]); + } +} diff --git a/src/main/java/frc/robot/subystem/ExampleSubsystem.java b/src/main/java/frc/robot/subystem/ExampleSubsystem.java deleted file mode 100644 index 5ccbeeb..0000000 --- a/src/main/java/frc/robot/subystem/ExampleSubsystem.java +++ /dev/null @@ -1,15 +0,0 @@ -package frc.robot.subystem; - -public class ExampleSubsystem { - private static ExampleSubsystem instance; - - // Important note: this is required. DO NOT just just only have a constructor. - // TRUST ME this is much easier to read and manage throughout the codebase. - public static ExampleSubsystem GetInstance() { - if (instance == null) { - instance = new ExampleSubsystem(); - } - - return instance; - } -} diff --git a/src/main/java/frc/robot/util/AlignmentPoints.java b/src/main/java/frc/robot/util/AlignmentPoints.java new file mode 100644 index 0000000..0eaf238 --- /dev/null +++ b/src/main/java/frc/robot/util/AlignmentPoints.java @@ -0,0 +1,182 @@ +package frc.robot.util; + +import java.util.Comparator; +import java.util.HashMap; +import java.util.Map; +import java.util.Optional; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.DriverStation.Alliance; +import lombok.Getter; +import lombok.Setter; + +public class AlignmentPoints { + @Setter + public static double kFieldWidth = 6.0; + @Setter + public static double kFieldLength = 6.0; + + private static AlignmentMap POINTS; + + /** + * Functional interface for providing the current robot position. + * Implement this to integrate with your odometry/position tracking system. + */ + @FunctionalInterface + public interface PositionSupplier { + Pose2d get(); + } + + private static PositionSupplier positionSupplier = () -> new Pose2d(); + + /** + * Set the position supplier for closest point calculations. + * @param supplier A supplier that returns the current robot Pose2d + */ + public static void setPositionSupplier(PositionSupplier supplier) { + positionSupplier = supplier; + } + + public static void setPoints(AlignmentMap points) { + POINTS = points; + } + + @Getter + public static class AlignmentMap { + private final Map>> points = new HashMap<>(); + + public AlignmentMap category(String name, CategoryBuilder builder) { + points.put(name, builder.build()); + return this; + } + + public Optional get(String category, String subCategory, String pointName) { + return Optional.ofNullable(points.get(category)) + .map(cat -> cat.get(subCategory)) + .map(sub -> sub.get(pointName)); + } + } + + public static class CategoryBuilder { + private final Map> subCategories = new HashMap<>(); + + public CategoryBuilder subCategory(String name, SubCategoryBuilder builder) { + subCategories.put(name, builder.build()); + return this; + } + + Map> build() { + return subCategories; + } + } + + public static class SubCategoryBuilder { + private final Map points = new HashMap<>(); + @Getter + private Pose2d center; + + public SubCategoryBuilder point(String name, double x, double y, double rotationRadians) { + points.put(name, new Pose2d(x, y, new Rotation2d(rotationRadians))); + return this; + } + + public SubCategoryBuilder point(String name, Pose2d pose) { + points.put(name, pose); + return this; + } + + Map build() { + double avgX = 0, avgY = 0, avgTheta = 0; + int count = points.size(); + if (count > 0) { + avgX = points.values().stream().mapToDouble(Pose2d::getX).sum() / count; + avgY = points.values().stream().mapToDouble(Pose2d::getY).sum() / count; + double sumSin = points.values().stream().mapToDouble(p -> Math.sin(p.getRotation().getRadians())).sum(); + double sumCos = points.values().stream().mapToDouble(p -> Math.cos(p.getRotation().getRadians())).sum(); + avgTheta = Math.atan2(sumSin / count, sumCos / count); + } + center = new Pose2d(avgX, avgY, new Rotation2d(avgTheta)); + + return points; + } + } + + private static Alliance alliance = Alliance.Blue; + + public static void setAlliance(Alliance fieldSide) { + alliance = fieldSide; + } + + public static Optional getPoint(String category, String subCategory, String pointName) { + return POINTS.get(category, subCategory, pointName) + .map(pose -> alliance == Alliance.Red ? mirrorPose(pose) : pose); + } + + public static Optional getPoint(String category) { + var subString = category.split(":"); + if (subString.length != 3) { + return Optional.empty(); + } + + String categoryName = subString[1]; + if (categoryName.toLowerCase().equals("closest")) { + categoryName = getClosestCategory(subString[0], positionSupplier.get()).orElse(null); + if (categoryName == null) { + return Optional.empty(); + } + } + + String pointName = subString[2]; + if (pointName.toLowerCase().equals("closest")) { + pointName = getClosestPoint(subString[0], categoryName, positionSupplier.get()).orElse(null); + if (pointName == null) { + return Optional.empty(); + } + } + + return getPoint(subString[0], categoryName, pointName); + } + + private static Optional getClosestPoint(String category, String subCategory, Pose2d position) { + var points = POINTS.getPoints().get(category).get(subCategory); + if (points == null) { + return Optional.empty(); + } + return points.entrySet().stream() + .min(Comparator.comparingDouble( + entry -> entry.getValue().getTranslation().getDistance(position.getTranslation()))) + .map(Map.Entry::getKey); + } + + private static Optional getClosestCategory(String category, Pose2d position) { + var cat = POINTS.getPoints().get(category); + if (cat == null) { + return Optional.empty(); + } + return cat.entrySet().stream() + .min(Comparator.comparingDouble( + entry -> calculateCenter(entry.getValue()).getTranslation().getDistance(position.getTranslation()))) + .map(Map.Entry::getKey); + } + + private static Pose2d calculateCenter(Map points) { + double avgX = 0, avgY = 0, avgTheta = 0; + int count = points.size(); + if (count > 0) { + avgX = points.values().stream().mapToDouble(Pose2d::getX).sum() / count; + avgY = points.values().stream().mapToDouble(Pose2d::getY).sum() / count; + double sumSin = points.values().stream().mapToDouble(p -> Math.sin(p.getRotation().getRadians())).sum(); + double sumCos = points.values().stream().mapToDouble(p -> Math.cos(p.getRotation().getRadians())).sum(); + avgTheta = Math.atan2(sumSin / count, sumCos / count); + } + return new Pose2d(avgX, avgY, new Rotation2d(avgTheta)); + } + + private static Pose2d mirrorPose(Pose2d pose) { + return new Pose2d( + kFieldLength - pose.getX(), + kFieldWidth - pose.getY(), + pose.getRotation().rotateBy(new Rotation2d(Math.PI))); + } +} diff --git a/src/main/java/frc/robot/util/CustomMath.java b/src/main/java/frc/robot/util/CustomMath.java new file mode 100644 index 0000000..2bd3cd5 --- /dev/null +++ b/src/main/java/frc/robot/util/CustomMath.java @@ -0,0 +1,23 @@ +package frc.robot.util; + +/** + * @note MathFun = Math Functions + * @apiNote this is the file where all of the math functions go + */ +public class CustomMath { + + /** + * Wraps an angle to the range [-180, 180] degrees. + * + * @param angle the angle in degrees + * @return the wrapped angle in degrees within [-180, 180] + */ + public static double wrapTo180(double angle) { + double newAngle = (angle + 180) % 360; + while (newAngle < 0) { + newAngle += 360; + } + + return newAngle - 180; + } +} diff --git a/src/main/java/frc/robot/util/OptionalAutobahn.java b/src/main/java/frc/robot/util/OptionalAutobahn.java deleted file mode 100644 index 4db84f0..0000000 --- a/src/main/java/frc/robot/util/OptionalAutobahn.java +++ /dev/null @@ -1,179 +0,0 @@ -package frc.robot.util; - -import java.util.ArrayList; -import java.util.List; -import java.util.Optional; -import java.util.concurrent.CompletableFuture; - -import autobahn.client.AutobahnClient; -import autobahn.client.NamedCallback; - -/* - * This class is a wrapper around the AutobahnClient class that allows for the client to be optional. - * This is useful for when the client is not yet connected to the network. - * It also allows for the client to be set and replayed when the client is set. - */ -public class OptionalAutobahn extends AutobahnClient { - private Optional autobahnClient = Optional.empty(); - - public OptionalAutobahn() { - super(null); // set fake. we aren't actually using this instance - } - - /** - * Cached subscription / unsubscription operations to replay once a real client - * is set. - */ - private final List cachedOperations = new ArrayList<>(); - - private enum OperationType { - SUBSCRIBE_SINGLE, - SUBSCRIBE_MULTI, - UNSUBSCRIBE_TOPIC, - UNSUBSCRIBE_CALLBACK - } - - private static class CachedOperation { - private final OperationType type; - private final String topic; - private final List topics; - private final NamedCallback callback; - - CachedOperation(OperationType type, String topic, NamedCallback callback) { - this.type = type; - this.topic = topic; - this.callback = callback; - this.topics = null; - } - - CachedOperation(OperationType type, List topics, NamedCallback callback) { - this.type = type; - this.topic = null; - this.callback = callback; - this.topics = new ArrayList<>(topics); - } - - CachedOperation(OperationType type, String topic) { - this.type = type; - this.topic = topic; - this.callback = null; - this.topics = null; - } - } - - /** Returns the underlying real client, if one has been configured. */ - public Optional getReal() { - return autobahnClient; - } - - @Override - public boolean isConnected() { - return autobahnClient.isPresent() && autobahnClient.get().isConnected(); - } - - /** - * Sets the real Autobahn client and replays any cached subscription / - * unsubscription - * operations against it. - */ - public void setAutobahnClient(AutobahnClient autobahnClient) { - this.autobahnClient = Optional.of(autobahnClient); - - // Replay all cached operations in the order they were recorded. - for (CachedOperation op : cachedOperations) { - switch (op.type) { - case SUBSCRIBE_SINGLE: - this.autobahnClient.get().subscribe(op.topic, op.callback); - break; - case SUBSCRIBE_MULTI: - this.autobahnClient.get().subscribe(op.topics, op.callback); - break; - case UNSUBSCRIBE_TOPIC: - this.autobahnClient.get().unsubscribe(op.topic); - break; - case UNSUBSCRIBE_CALLBACK: - this.autobahnClient.get().unsubscribe(op.topic, op.callback); - break; - default: - break; - } - } - - cachedOperations.clear(); - } - - /** - * Publishes a message. If the real client is not yet present, this is a no-op - * and the - * publish is dropped (nothing is cached or replayed later). - */ - @Override - public CompletableFuture publish(String topic, byte[] payload) { - if (autobahnClient.isPresent()) { - return autobahnClient.get().publish(topic, payload); - } - - // Drop publishes when there is no real client yet. - return CompletableFuture.completedFuture(null); - } - - /** - * Subscribes to a topic. If the real client is not yet present, this call is - * cached and - * will be replayed when {@link #setAutobahnClient(AutobahnClient)} is called. - */ - @Override - public CompletableFuture subscribe(String topic, NamedCallback callback) { - if (autobahnClient.isPresent()) { - return autobahnClient.get().subscribe(topic, callback); - } - - cachedOperations.add(new CachedOperation(OperationType.SUBSCRIBE_SINGLE, topic, callback)); - return CompletableFuture.completedFuture(null); - } - - /** - * Subscribes to multiple topics with the same callback. If the real client is - * not yet - * present, this call is cached and will be replayed when the client is set. - */ - @Override - public CompletableFuture subscribe(List topics, NamedCallback callback) { - if (autobahnClient.isPresent()) { - return autobahnClient.get().subscribe(topics, callback); - } - - cachedOperations.add(new CachedOperation(OperationType.SUBSCRIBE_MULTI, topics, callback)); - return CompletableFuture.completedFuture(null); - } - - /** - * Unsubscribes from a topic. If the real client is not yet present, this - * operation is - * cached and will be replayed when the client is set. - */ - @Override - public CompletableFuture unsubscribe(String topic) { - if (autobahnClient.isPresent()) { - return autobahnClient.get().unsubscribe(topic); - } - - cachedOperations.add(new CachedOperation(OperationType.UNSUBSCRIBE_TOPIC, topic)); - return CompletableFuture.completedFuture(null); - } - - /** - * Unsubscribes a specific callback from a topic. If the real client is not yet - * present, - * this operation is cached and will be replayed when the client is set. - */ - @Override - public CompletableFuture unsubscribe(String topic, NamedCallback callback) { - if (autobahnClient.isPresent()) { - return autobahnClient.get().unsubscribe(topic, callback); - } - - cachedOperations.add(new CachedOperation(OperationType.UNSUBSCRIBE_CALLBACK, topic, callback)); - return CompletableFuture.completedFuture(null); - } -} diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json index 1bd137a..162ad66 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,35 +1,35 @@ { - "fileName": "AdvantageKit.json", - "name": "AdvantageKit", - "version": "4.1.2", - "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", - "frcYear": "2026", - "mavenUrls": [ - "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" - ], - "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", - "javaDependencies": [ - { - "groupId": "org.littletonrobotics.akit", - "artifactId": "akit-java", - "version": "4.1.2" - } - ], - "jniDependencies": [ - { - "groupId": "org.littletonrobotics.akit", - "artifactId": "akit-wpilibio", - "version": "4.1.2", - "skipInvalidPlatforms": false, - "isJar": false, - "validPlatforms": [ - "linuxathena", - "linuxx86-64", - "linuxarm64", - "osxuniversal", - "windowsx86-64" - ] - } - ], - "cppDependencies": [] -} + "fileName": "AdvantageKit.json", + "name": "AdvantageKit", + "version": "26.0.0", + "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", + "frcYear": "2026", + "mavenUrls": [ + "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" + ], + "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", + "javaDependencies": [ + { + "groupId": "org.littletonrobotics.akit", + "artifactId": "akit-java", + "version": "26.0.0" + } + ], + "jniDependencies": [ + { + "groupId": "org.littletonrobotics.akit", + "artifactId": "akit-wpilibio", + "version": "26.0.0", + "skipInvalidPlatforms": false, + "isJar": false, + "validPlatforms": [ + "linuxathena", + "linuxx86-64", + "linuxarm64", + "osxuniversal", + "windowsx86-64" + ] + } + ], + "cppDependencies": [] +} \ No newline at end of file diff --git a/vendordeps/Phoenix5-5.35.1.json b/vendordeps/Phoenix5-5.35.1.json deleted file mode 100644 index 6463fb1..0000000 --- a/vendordeps/Phoenix5-5.35.1.json +++ /dev/null @@ -1,169 +0,0 @@ -{ - "fileName": "Phoenix5-5.35.1.json", - "name": "CTRE-Phoenix (v5)", - "version": "5.35.1", - "frcYear": "2026", - "uuid": "ab676553-b602-441f-a38d-f1296eff6537", - "mavenUrls": ["https://maven.ctr-electronics.com/release/"], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json", - "requires": [ - { - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", - "offlineFileName": "Phoenix6-frc2025-latest.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json" - } - ], - "conflictsWith": [ - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", - "offlineFileName": "Phoenix6-replay-frc2025-latest.json" - }, - { - "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", - "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", - "offlineFileName": "Phoenix5-replay-frc2025-latest.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "api-java", - "version": "5.35.1" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "wpiapi-java", - "version": "5.35.1" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.35.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.35.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "wpiapi-cpp", - "version": "5.35.1", - "libName": "CTRE_Phoenix_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "api-cpp", - "version": "5.35.1", - "libName": "CTRE_Phoenix", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.35.1", - "libName": "CTRE_PhoenixCCI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "5.35.1", - "libName": "CTRE_Phoenix_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "api-cpp-sim", - "version": "5.35.1", - "libName": "CTRE_PhoenixSim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.35.1", - "libName": "CTRE_PhoenixCCISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} diff --git a/vendordeps/Phoenix5-5.36.0.json b/vendordeps/Phoenix5-5.36.0.json new file mode 100644 index 0000000..9a27e47 --- /dev/null +++ b/vendordeps/Phoenix5-5.36.0.json @@ -0,0 +1,171 @@ +{ + "fileName": "Phoenix5-5.36.0.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.36.0", + "frcYear": "2026", + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2026-latest.json", + "requires": [ + { + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", + "offlineFileName": "Phoenix6-frc2026-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json" + } + ], + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" + }, + { + "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", + "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", + "offlineFileName": "Phoenix5-replay-frc2026-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.36.0" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.36.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.36.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.36.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.36.0", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.36.0", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.36.0", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.36.0", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.36.0", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.36.0", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/vendordeps/Phoenix6-25.2.2.json b/vendordeps/Phoenix6-25.2.2.json deleted file mode 100644 index abfe8b8..0000000 --- a/vendordeps/Phoenix6-25.2.2.json +++ /dev/null @@ -1,417 +0,0 @@ -{ - "fileName": "Phoenix6-25.2.2.json", - "name": "CTRE-Phoenix (v6)", - "version": "25.2.2", - "frcYear": "2026", - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "mavenUrls": ["https://maven.ctr-electronics.com/release/"], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", - "conflictsWith": [ - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", - "offlineFileName": "Phoenix6-replay-frc2025-latest.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "25.2.2" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "api-cpp", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "api-cpp-sim", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "25.2.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-cpp", - "version": "25.2.2", - "libName": "CTRE_Phoenix6_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.2.2", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "25.2.2", - "libName": "CTRE_Phoenix6_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "25.2.2", - "libName": "CTRE_PhoenixTools_Sim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "25.2.2", - "libName": "CTRE_SimTalonSRX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "25.2.2", - "libName": "CTRE_SimVictorSPX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "25.2.2", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.2.2", - "libName": "CTRE_SimCANCoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.2.2", - "libName": "CTRE_SimProTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "25.2.2", - "libName": "CTRE_SimProTalonFXS", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "25.2.2", - "libName": "CTRE_SimProCANcoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "25.2.2", - "libName": "CTRE_SimProPigeon2", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "25.2.2", - "libName": "CTRE_SimProCANrange", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} diff --git a/vendordeps/Phoenix6-26.1.0.json b/vendordeps/Phoenix6-26.1.0.json new file mode 100644 index 0000000..dc5dc62 --- /dev/null +++ b/vendordeps/Phoenix6-26.1.0.json @@ -0,0 +1,449 @@ +{ + "fileName": "Phoenix6-26.1.0.json", + "name": "CTRE-Phoenix (v6)", + "version": "26.1.0", + "frcYear": "2026", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json", + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "26.1.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "api-cpp-sim", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "26.1.0", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "26.1.0", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "26.1.0", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "26.1.0", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "26.1.0", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "26.1.0", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "26.1.0", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "26.1.0", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "26.1.0", + "libName": "CTRE_SimProTalonFXS", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "26.1.0", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "26.1.0", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "26.1.0", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "26.1.0", + "libName": "CTRE_SimProCANdi", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "26.1.0", + "libName": "CTRE_SimProCANdle", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/vendordeps/REVLib-2025.0.2.json b/vendordeps/REVLib-2025.0.2.json deleted file mode 100644 index 04783ab..0000000 --- a/vendordeps/REVLib-2025.0.2.json +++ /dev/null @@ -1,69 +0,0 @@ -{ - "fileName": "REVLib-2025.0.2.json", - "name": "REVLib", - "version": "2025.0.2", - "frcYear": "2026", - "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", - "mavenUrls": ["https://maven.revrobotics.com/"], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json", - "javaDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-java", - "version": "2025.0.2" - } - ], - "jniDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-driver", - "version": "2025.0.2", - "skipInvalidPlatforms": true, - "isJar": false, - "validPlatforms": [ - "windowsx86-64", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ], - "cppDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-cpp", - "version": "2025.0.2", - "libName": "REVLib", - "headerClassifier": "headers", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - }, - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-driver", - "version": "2025.0.2", - "libName": "REVLibDriver", - "headerClassifier": "headers", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ] -} diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 0000000..4f96af8 --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,133 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2026.0.0", + "frcYear": "2026", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2026.0.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2026.0.0", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2026.0.0", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.0", + "libName": "BackendDriver", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.0", + "libName": "REVLibWpi", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file