mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Add ProfiledPID command to RapidReactCommandBot (#7030)
This commit is contained in:
@@ -29,6 +29,23 @@ inline constexpr double kEncoderDistancePerPulse =
|
||||
// Assumes the encoders are directly mounted on the wheel shafts
|
||||
((kWheelDiameter * std::numbers::pi) / kEncoderCPR).value();
|
||||
|
||||
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
|
||||
// These values MUST be determined either experimentally or theoretically for
|
||||
// *your* robot's drive. The SysId tool provides a convenient method for
|
||||
// obtaining feedback and feedforward values for your robot.
|
||||
inline constexpr double kTurnP = 1;
|
||||
inline constexpr double kTurnI = 0;
|
||||
inline constexpr double kTurnD = 0;
|
||||
|
||||
inline constexpr auto kTurnTolerance = 5_deg;
|
||||
inline constexpr auto kTurnRateTolerance = 10_deg_per_s;
|
||||
|
||||
inline constexpr auto kMaxTurnRate = 100_deg_per_s;
|
||||
inline constexpr auto kMaxTurnAcceleration = 300_deg_per_s / 1_s;
|
||||
|
||||
inline constexpr auto ks = 1_V;
|
||||
inline constexpr auto kv = 0.8_V * 1_s / 1_deg;
|
||||
inline constexpr auto ka = 0.15_V * 1_s * 1_s / 1_deg;
|
||||
} // namespace DriveConstants
|
||||
|
||||
namespace IntakeConstants {
|
||||
|
||||
Reference in New Issue
Block a user