diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h index 22564c645a..986a49ad49 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h +++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h @@ -32,7 +32,7 @@ constexpr int kRightEncoderPorts[]{2, 3}; constexpr bool kLeftEncoderReversed = false; constexpr bool kRightEncoderReversed = true; -constexpr auto kTrackwidth = 0.6_m; +constexpr auto kTrackwidth = 0.69_m; constexpr frc::DifferentialDriveKinematics kDriveKinematics(kTrackwidth); constexpr int kEncoderCPR = 1024; @@ -45,15 +45,15 @@ constexpr bool kGyroReversed = true; // 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 +// theoretically for *your* robot's drive. The Robot Characterization // Toolsuite provides a convenient tool for obtaining these values for your // robot. -constexpr auto ks = 1_V; -constexpr auto kv = 0.8 * 1_V * 1_s / 1_m; -constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m; +constexpr auto ks = 0.22_V; +constexpr auto kv = 1.98 * 1_V * 1_s / 1_m; +constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m; // Example value only - as above, this must be tuned for your drive! -constexpr double kPDriveVel = 0.5; +constexpr double kPDriveVel = 8.5; } // namespace DriveConstants namespace AutoConstants { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java index 7d47655e32..f70a00301c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java @@ -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 {