Skip to content

Commit

Permalink
Fix up comments and incorrect unit
Browse files Browse the repository at this point in the history
  • Loading branch information
Gold856 committed Oct 2, 2024
1 parent 7aebff3 commit 5bb657b
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@ 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;
Expand All @@ -39,10 +43,6 @@ 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;

// 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 SysId tool provides a convenient
// method for obtaining these values for your robot.
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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,10 @@ public static final class DriveConstants {
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterMeters * Math.PI) / kEncoderCPR;

// 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.
public static final double kTurnP = 1;
public static final double kTurnI = 0;
public static final double kTurnD = 0;
Expand All @@ -42,10 +46,6 @@ public static final class DriveConstants {
public static final double kMaxTurnRateDegPerS = 100;
public static final double kMaxTurnAccelerationDegPerSSquared = 300;

// 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 SysId tool provides a convenient method for obtaining these values for your robot.
public static final double ksVolts = 1;
public static final double kvVoltSecondsPerDegree = 0.8;
public static final double kaVoltSecondsSquaredPerDegree = 0.15;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;

import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.DegreesPerSecond;
import static edu.wpi.first.units.Units.Volts;

import edu.wpi.first.epilogue.Logged;
Expand Down Expand Up @@ -144,7 +144,7 @@ public Command turnToAngleCommand(double angleDeg) {
m_controller.calculate(m_gyro.getRotation2d().getDegrees(), angleDeg)
// Divide feedforward voltage by battery voltage to normalize it to [-1, 1]
+ m_feedforward
.calculate(RadiansPerSecond.of(m_controller.getSetpoint().velocity))
.calculate(DegreesPerSecond.of(m_controller.getSetpoint().velocity))
.in(Volts)
/ RobotController.getBatteryVoltage()))
.until(m_controller::atGoal)
Expand Down

0 comments on commit 5bb657b

Please sign in to comment.