From 4dcc2c784e3beaac966458729164766de2e0748b Mon Sep 17 00:00:00 2001 From: Griffin Date: Wed, 19 Feb 2025 16:51:57 -0500 Subject: [PATCH] added settings.json --- src/main/deploy/pathplanner/settings.json | 32 +++++++++++++++++++++ src/main/java/frc/robot/DriverJoystick.java | 30 +++++++++---------- 2 files changed, 47 insertions(+), 15 deletions(-) create mode 100644 src/main/deploy/pathplanner/settings.json diff --git a/src/main/deploy/pathplanner/settings.json b/src/main/deploy/pathplanner/settings.json new file mode 100644 index 0000000..5bf438c --- /dev/null +++ b/src/main/deploy/pathplanner/settings.json @@ -0,0 +1,32 @@ +{ + "robotWidth": 0.9, + "robotLength": 0.9, + "holonomicMode": true, + "pathFolders": [], + "autoFolders": [], + "defaultMaxVel": 3.0, + "defaultMaxAccel": 3.0, + "defaultMaxAngVel": 540.0, + "defaultMaxAngAccel": 720.0, + "defaultNominalVoltage": 12.0, + "robotMass": 74.088, + "robotMOI": 6.883, + "robotTrackwidth": 0.546, + "driveWheelRadius": 0.048, + "driveGearing": 5.143, + "maxDriveSpeed": 5.45, + "driveMotorType": "krakenX60", + "driveCurrentLimit": 60.0, + "wheelCOF": 1.2, + "flModuleX": 0.273, + "flModuleY": 0.273, + "frModuleX": 0.273, + "frModuleY": -0.273, + "blModuleX": -0.273, + "blModuleY": 0.273, + "brModuleX": -0.273, + "brModuleY": -0.273, + "bumperOffsetX": 0.0, + "bumperOffsetY": 0.0, + "robotFeatures": [] +} \ No newline at end of file diff --git a/src/main/java/frc/robot/DriverJoystick.java b/src/main/java/frc/robot/DriverJoystick.java index eabb697..ec74759 100644 --- a/src/main/java/frc/robot/DriverJoystick.java +++ b/src/main/java/frc/robot/DriverJoystick.java @@ -94,21 +94,21 @@ private DriverJoystick() { // Lock the wheels into an X formation super.xButton.whileTrue(this.driveTrain.setX()); - // super.aButton.whileTrue( - // new InstantCommand(() -> { - // this.currentPose = this.driveTrain.getState().Pose; - // }).andThen(AutoBuilder.followPath(new PathPlannerPath( - // PathPlannerPath.waypointsFromPoses(this.currentPose, - // DriveWaypoints.Algae23.getEndpoint()), - // new PathConstraints( - // DriveConstants.MaxSpeed, - // AutoConstants.kMaxAccelerationMetersPerSecondSquared, - // AutoConstants.kMaxAngularSpeedRadiansPerSecond, - // AutoConstants.kMaxAngularSpeedRadiansPerSecondSquared), - // new IdealStartingState( - // driveTrain.getState().Speeds.vxMetersPerSecond, - // driveTrain.getState().Pose.getRotation()), - // new GoalEndState(0, Rotation2d.kZero))))); + super.aButton.whileTrue( + new InstantCommand(() -> { + this.currentPose = this.driveTrain.getState().Pose; + }).andThen(AutoBuilder.followPath(new PathPlannerPath( + PathPlannerPath.waypointsFromPoses(this.currentPose, + DriveWaypoints.Algae23.getEndpoint()), + new PathConstraints( + DriveConstants.MaxSpeed, + AutoConstants.kMaxAccelerationMetersPerSecondSquared, + AutoConstants.kMaxAngularSpeedRadiansPerSecond, + AutoConstants.kMaxAngularSpeedRadiansPerSecondSquared), + new IdealStartingState( + driveTrain.getState().Speeds.vxMetersPerSecond, + driveTrain.getState().Pose.getRotation()), + new GoalEndState(0, Rotation2d.kZero))))); } /**