Skip to content
This repository has been archived by the owner on Jan 2, 2025. It is now read-only.

Commit

Permalink
fix gyro drive + drive constants
Browse files Browse the repository at this point in the history
  • Loading branch information
jack60612 committed Feb 26, 2024
1 parent bc51bc4 commit 21e0d8e
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 11 deletions.
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/DriveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,21 +31,21 @@ public final class DriveConstants {
// The Robot Characterization Toolsuite provides a convenient tool for obtaining these
// values for your robot.
// Feed Forward Constants
public static final double ksDriveVolts = 0.16213;
public static final double kvDriveVoltSecondsPerMeter = 2.2194;
public static final double kaDriveVoltSecondsSquaredPerMeter = 0.33599;
public static final double ksDriveVolts = 0.19676;
public static final double kvDriveVoltSecondsPerMeter = 2.2623;
public static final double kaDriveVoltSecondsSquaredPerMeter = 0.43785;
// Max speed Constants
public static final double kMaxOutputDrive = 1.0;
public static final double kMinOutputDrive = -1.0;
public static final double kMaxOutputDrive = 0.8;
public static final double kMinOutputDrive = -0.8;
// Feed Back / PID Constants
public static final double kPDriveVel = 0.00034388;
public static final double kPDriveVel = 0.00088622;
public static final double kIDriveVel = 0.0;
public static final double kDDriveVel = 0.0;
public static final double kIzDriveVel = 0.0; // error before integral takes effect

public static final double kPDrivePos = 5.7745;
public static final double kPDrivePos = 4.6269;
public static final double kIDrivePos = 0.0;
public static final double kDDrivePos = 0.55289;
public static final double kDDrivePos = 0.49649;
public static final double kIzDrivePos = 0.0; // error before integral takes effect
// Helper class that converts a chassis velocity (dx and dtheta components) to left and right
// wheel velocities for a differential drive.
Expand Down
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.Constants.CANConstants;
import frc.robot.Constants;
import frc.robot.DriveConstants;

/** This Subsystem is what allows the code to interact with the drivetrain of the robot. */
Expand Down Expand Up @@ -76,8 +77,8 @@ public class DriveSubsystem extends SubsystemBase {
static final double turn_P = 0.1;
static final double turn_I = 0.00;
static final double turn_D = 0.00;
static final double MaxTurnRateDegPerS = 20;
static final double MaxTurnAccelerationDegPerSSquared = 50;
static final double MaxTurnRateDegPerS = 5;
static final double MaxTurnAccelerationDegPerSSquared = 10;
static final double TurnToleranceDeg = 3; // max diff in degrees
static final double TurnRateToleranceDegPerS = 10; // degrees per second
// false when inactive, true when active / a target is set.
Expand Down Expand Up @@ -370,7 +371,7 @@ public void driveStraight(
}
double leftStickValue = joystickMagnitude + angleRate;
double rightStickValue = joystickMagnitude - angleRate;
this.tankDrive(leftStickValue, rightStickValue);
this.tankDrive((leftStickValue * Constants.MAX_SPEED), (rightStickValue * Constants.MAX_SPEED));
}

/*
Expand Down

0 comments on commit 21e0d8e

Please sign in to comment.