mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Update characterization values to match real robot (#2183)
This is in preparation for an end-to-end trajectory tutorial example. Co-Authored-By: Dalton Smith <gamefollower26@gmail.com>
This commit is contained in:
@@ -29,7 +29,7 @@ public final class Constants {
|
||||
public static final boolean kLeftEncoderReversed = false;
|
||||
public static final boolean kRightEncoderReversed = true;
|
||||
|
||||
public static final double kTrackwidthMeters = 0.6;
|
||||
public static final double kTrackwidthMeters = 0.69;
|
||||
public static final DifferentialDriveKinematics kDriveKinematics =
|
||||
new DifferentialDriveKinematics(kTrackwidthMeters);
|
||||
|
||||
@@ -44,14 +44,14 @@ public final class Constants {
|
||||
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
|
||||
// These characterization values MUST be determined either experimentally or theoretically
|
||||
// for *your* robot's drive.
|
||||
// The RobotPy Characterization Toolsuite provides a convenient tool for obtaining these
|
||||
// The Robot Characterization Toolsuite provides a convenient tool for obtaining these
|
||||
// values for your robot.
|
||||
public static final double ksVolts = 1;
|
||||
public static final double kvVoltSecondsPerMeter = 0.8;
|
||||
public static final double kaVoltSecondsSquaredPerMeter = 0.15;
|
||||
public static final double ksVolts = 0.22;
|
||||
public static final double kvVoltSecondsPerMeter = 1.98;
|
||||
public static final double kaVoltSecondsSquaredPerMeter = 0.2;
|
||||
|
||||
// Example value only - as above, this must be tuned for your drive!
|
||||
public static final double kPDriveVel = 0.5;
|
||||
public static final double kPDriveVel = 8.5;
|
||||
}
|
||||
|
||||
public static final class OIConstants {
|
||||
|
||||
Reference in New Issue
Block a user