From 4d20c5064279d9e0ac890c93e644e81dbabf929c Mon Sep 17 00:00:00 2001 From: Zach Wilke <83995467+C4llSqin@users.noreply.github.com> Date: Sat, 11 Oct 2025 15:24:47 -0600 Subject: [PATCH] commit for robot swithc camera angles l3 and l4 scoring distances --- .../autos/1 Coral Center Barge Bottom.auto | 31 +++++++++++ .../pathplanner/paths/New New Path.path | 54 +++++++++++++++++++ .../robot/constants/BuildConstants.java | 10 ++-- .../frc4388/robot/constants/Constants.java | 8 +-- 4 files changed, 94 insertions(+), 9 deletions(-) create mode 100644 src/main/deploy/pathplanner/autos/1 Coral Center Barge Bottom.auto create mode 100644 src/main/deploy/pathplanner/paths/New New Path.path diff --git a/src/main/deploy/pathplanner/autos/1 Coral Center Barge Bottom.auto b/src/main/deploy/pathplanner/autos/1 Coral Center Barge Bottom.auto new file mode 100644 index 0000000..49c8daa --- /dev/null +++ b/src/main/deploy/pathplanner/autos/1 Coral Center Barge Bottom.auto @@ -0,0 +1,31 @@ +{ + "version": "2025.0", + "command": { + "type": "sequential", + "data": { + "commands": [ + { + "type": "path", + "data": { + "pathName": "Center Barge to Reef 4 Left" + } + }, + { + "type": "named", + "data": { + "name": "place-coral-left-l4" + } + }, + { + "type": "path", + "data": { + "pathName": "Reef 4 to Bottom Feed" + } + } + ] + } + }, + "resetOdom": true, + "folder": null, + "choreoAuto": false +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/New New Path.path b/src/main/deploy/pathplanner/paths/New New Path.path new file mode 100644 index 0000000..357d460 --- /dev/null +++ b/src/main/deploy/pathplanner/paths/New New Path.path @@ -0,0 +1,54 @@ +{ + "version": "2025.0", + "waypoints": [ + { + "anchor": { + "x": 1.0769318181818182, + "y": 4.015028409090909 + }, + "prevControl": null, + "nextControl": { + "x": 1.997888002510365, + "y": 4.015028409090909 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 2.8618465909090913, + "y": 4.015028409090909 + }, + "prevControl": { + "x": 2.094034090909091, + "y": 4.015028409090909 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "pointTowardsZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 1.0, + "maxAcceleration": 1.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0, + "nominalVoltage": 12.0, + "unlimited": false + }, + "goalEndState": { + "velocity": 0, + "rotation": 0.0 + }, + "reversed": false, + "folder": null, + "idealStartingState": { + "velocity": 0, + "rotation": 0.0 + }, + "useDefaultConstraints": false +} \ No newline at end of file diff --git a/src/main/java/frc4388/robot/constants/BuildConstants.java b/src/main/java/frc4388/robot/constants/BuildConstants.java index e9a0dd5..bfbf8d0 100644 --- a/src/main/java/frc4388/robot/constants/BuildConstants.java +++ b/src/main/java/frc4388/robot/constants/BuildConstants.java @@ -7,12 +7,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "2025RidgeScape"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 181; - public static final String GIT_SHA = "ba0cfce5774aac2b4e8c86abf532cbc0cac1ee7a"; - public static final String GIT_DATE = "2025-10-10 18:51:29 MDT"; + public static final int GIT_REVISION = 182; + public static final String GIT_SHA = "88a4a00c29a2e2bdd9c14715807a8fd26499f9cf"; + public static final String GIT_DATE = "2025-10-10 20:22:54 MDT"; public static final String GIT_BRANCH = "advantagekit"; - public static final String BUILD_DATE = "2025-10-10 20:08:21 MDT"; - public static final long BUILD_UNIX_TIME = 1760148501289L; + public static final String BUILD_DATE = "2025-10-11 14:12:35 MDT"; + public static final long BUILD_UNIX_TIME = 1760213555484L; public static final int DIRTY = 1; private BuildConstants(){} diff --git a/src/main/java/frc4388/robot/constants/Constants.java b/src/main/java/frc4388/robot/constants/Constants.java index 9f0789e..85cdaaa 100644 --- a/src/main/java/frc4388/robot/constants/Constants.java +++ b/src/main/java/frc4388/robot/constants/Constants.java @@ -76,11 +76,11 @@ public final class Constants { // X is tangent to reef side // Y is normal to reef side public static final double X_SCORING_POSITION_OFFSET = Units.inchesToMeters(6.5+1); // This is from the field - public static final double Y_SCORING_POSITION_OFFSET = Units.inchesToMeters(16-2); + public static final double Y_SCORING_POSITION_OFFSET = Units.inchesToMeters(16); public static final double HALF_ROBOT_SIZE = Units.inchesToMeters(18); public static final double L4_DISTANCE_PREP = HALF_ROBOT_SIZE + Units.inchesToMeters(15 - 6); - public static final double L4_DISTANCE_SCORE = L4_DISTANCE_PREP + Units.inchesToMeters(-4-4); + public static final double L4_DISTANCE_SCORE = L4_DISTANCE_PREP + Units.inchesToMeters(-4-2); // public static final double L4_DISTANCE_SCORE = HALF_ROBOT_SIZE + Units.inchesToMeters(4.5); public static final double L3_DISTANCE_PREP = HALF_ROBOT_SIZE + Units.inchesToMeters(15); @@ -114,8 +114,8 @@ public final class Constants { public static final String LEFT_CAMERA_NAME = "CAMERA_LEFT"; public static final String RIGHT_CAMERA_NAME = "CAMERA_RIGHT"; - public static final Transform3d LEFT_CAMERA_POS = new Transform3d(new Translation3d(Units.inchesToMeters(5.3 - 1), Units.inchesToMeters(8.75 + 2), Units.inchesToMeters(9)), new Rotation3d(0,0.0,-19.0 * Math.PI / 180)); - public static final Transform3d RIGHT_CAMERA_POS = new Transform3d(new Translation3d(Units.inchesToMeters(5.3 -2), Units.inchesToMeters(-8.75 + 2), Units.inchesToMeters(9)), new Rotation3d(0,0.0,20.0 * Math.PI / 180)); + public static final Transform3d LEFT_CAMERA_POS = new Transform3d(new Translation3d(Units.inchesToMeters(5.3 - 1), Units.inchesToMeters(8.75), Units.inchesToMeters(9)), new Rotation3d(0,0.0,-16.0 * Math.PI / 180)); + public static final Transform3d RIGHT_CAMERA_POS = new Transform3d(new Translation3d(Units.inchesToMeters(5.3 -2), Units.inchesToMeters(-8.75), Units.inchesToMeters(9)), new Rotation3d(0,0.0,22.0 * Math.PI / 180)); public static final double MIN_ESTIMATION_DISTANCE = 2; // Meters