Class DriveBaseSubsystemConfig
java.lang.Object
frc.robot.shared.config.AbstractConfig
frc.robot.shared.config.AbstractSubsystemConfig
frc.robot.subsystems.drivebase.config.DriveBaseSubsystemConfig
Configuration bundle for the drive base subsystem. The values are mirrored to SmartDashboard so they can be tuned live without redeploying
firmware.
-
Nested Class Summary
Nested classes/interfaces inherited from class frc.robot.shared.config.AbstractConfig
AbstractConfig.ComponentPoseConfig -
Field Summary
FieldsModifier and TypeFieldDescriptionbooleanWhether state-based power management (shooting speed scale) applies during autonomous mode.doublePercentage of maximum drive speed applied when battery voltage is belowcriticalVoltageThresholdVolts.doubleBattery voltage threshold indicating severe sag.doubleMargin in degrees around each field-facing orientation (0 and 180 degrees) within which the robot is considered to already be facing that direction.booleanWhether YAGSL heading correction is enabled.doublePercentage of maximum drive speed applied when battery voltage is belowlowVoltageThresholdVoltsbut abovecriticalVoltageThresholdVolts.doubleBattery voltage threshold below which the drive base begins scaling speed to conserve power.doubleMaximum angular speed in degrees per second.doubleMaximum linear speed in feet per second.PID gains for the path following rotation controller.PID gains for the path following translation controller.doubleAllowed heading error in degrees.doublePercentage of maximum drive speed allowed when the robot is actively shooting (FIRE_READY or AUTO_CYCLE).doubleAdditional rotation scale applied in simulation.doubleAdditional translation scale applied in simulation.Name of the swerve configuration directory under the deploy folder (e.g., "swerve" or "swerve-test").SysId routine parameters shared by all drive base motors (drive and angle).Fields inherited from class frc.robot.shared.config.AbstractSubsystemConfig
enabled, verbose -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptiondoubleReads the critical-voltage speed scale as a fraction (0.0–1.0).doubleReads the battery voltage threshold below which critical-voltage speed scaling activates.Supplies the field-facing margin in radians.doubleReads the low-voltage speed scale as a fraction (0.0–1.0).doubleReads the battery voltage threshold below which low-voltage speed scaling activates.Supplies the maximum angular speed in radians per second.Supplies the maximum linear speed in meters per second.Returns the path following rotation PID config.Returns the path following translation PID config.Supplies the rotation tolerance in radians.doubleReads the shooting speed scale as a fraction (0.0–1.0).Supplies the additional joystick rotation scale applied during simulation.Supplies the additional joystick translation scale applied during simulation.Returns the swerve configuration directory name relative to the deploy folder.booleanReturns whether state-based power management applies during autonomous mode.booleanReturns whether YAGSL heading correction is enabled.Methods inherited from class frc.robot.shared.config.AbstractSubsystemConfig
getVerboseMethods inherited from class frc.robot.shared.config.AbstractConfig
getDashboardPrefix, initializeNestedDashboardPrefixes, readTunableBoolean, readTunableDegrees, readTunableDegreesAsRadians, readTunableNumber, readTunableString, setDashboardPrefix
-
Field Details
-
maximumLinearSpeedFeetPerSecond
public double maximumLinearSpeedFeetPerSecondMaximum linear speed in feet per second. -
maximumAngularSpeedDegreesPerSecond
public double maximumAngularSpeedDegreesPerSecondMaximum angular speed in degrees per second. -
rotationToleranceDegrees
public double rotationToleranceDegreesAllowed heading error in degrees. -
fieldFacingMarginDegrees
public double fieldFacingMarginDegreesMargin in degrees around each field-facing orientation (0 and 180 degrees) within which the robot is considered to already be facing that direction. Used by the snap-to-field-facing command to decide whether to flip to the opposite heading. -
sysId
SysId routine parameters shared by all drive base motors (drive and angle). -
pathTranslation
PID gains for the path following translation controller. -
pathRotation
PID gains for the path following rotation controller. -
simulationTranslationScale
public double simulationTranslationScaleAdditional translation scale applied in simulation. -
simulationOmegaScale
public double simulationOmegaScaleAdditional rotation scale applied in simulation. -
swerveConfigDirectory
Name of the swerve configuration directory under the deploy folder (e.g., "swerve" or "swerve-test"). -
headingCorrectionEnabled
public boolean headingCorrectionEnabledWhether YAGSL heading correction is enabled. Heading correction passively counteracts gyro drift during straight-line driving.Disable in simulation where the correction assumes real-world friction and inertia.
-
shootingSpeedScalePercent
public double shootingSpeedScalePercentPercentage of maximum drive speed allowed when the robot is actively shooting (FIRE_READY or AUTO_CYCLE). A value of 70 means the drive base runs at 70% of its configured max speed while the shooter, indexer, and feeder are powered, reducing current draw so the shooter maintains full accuracy. -
lowVoltageThresholdVolts
public double lowVoltageThresholdVoltsBattery voltage threshold below which the drive base begins scaling speed to conserve power. When the smoothed battery voltage drops below this value, the drive base applieslowVoltageSpeedScalePercentas an additional multiplier. -
lowVoltageSpeedScalePercent
public double lowVoltageSpeedScalePercentPercentage of maximum drive speed applied when battery voltage is belowlowVoltageThresholdVoltsbut abovecriticalVoltageThresholdVolts. -
criticalVoltageThresholdVolts
public double criticalVoltageThresholdVoltsBattery voltage threshold indicating severe sag. When the smoothed battery voltage drops below this value, the drive base applies the more aggressivecriticalVoltageSpeedScalePercentmultiplier. -
criticalVoltageSpeedScalePercent
public double criticalVoltageSpeedScalePercentPercentage of maximum drive speed applied when battery voltage is belowcriticalVoltageThresholdVolts. -
applyPowerManagementInAuto
public boolean applyPowerManagementInAutoWhether state-based power management (shooting speed scale) applies during autonomous mode. When false, only voltage-based scaling is active during auto; the shooting speed scale is skipped so PathPlanner path-following accuracy is preserved.
-
-
Constructor Details
-
DriveBaseSubsystemConfig
public DriveBaseSubsystemConfig()
-
-
Method Details
-
getSwerveConfigDirectory
Returns the swerve configuration directory name relative to the deploy folder.- Returns:
- directory name such as "swerve" or "swerve-test"
-
getMaximumLinearSpeedMetersPerSecond
Supplies the maximum linear speed in meters per second.- Returns:
- supplier yielding the current max linear speed (m/s)
-
getMaximumAngularSpeedRadiansPerSecond
Supplies the maximum angular speed in radians per second.- Returns:
- supplier yielding the current max angular speed (rad/s)
-
isHeadingCorrectionEnabled
public boolean isHeadingCorrectionEnabled()Returns whether YAGSL heading correction is enabled.- Returns:
- true when heading correction should be active
-
getSimulationTranslationScale
Supplies the additional joystick translation scale applied during simulation.- Returns:
- supplier yielding the current simulation translation scale (0–1)
-
getSimulationOmegaScale
Supplies the additional joystick rotation scale applied during simulation.- Returns:
- supplier yielding the current simulation rotation scale (0–1)
-
getRotationToleranceRadians
Supplies the rotation tolerance in radians.- Returns:
- supplier yielding the current rotation tolerance (rad)
-
getFieldFacingMarginRadians
Supplies the field-facing margin in radians. The robot is considered "facing" a field-aligned heading when it is within this many radians of that heading.- Returns:
- supplier yielding the current field-facing margin (rad)
-
getPathTranslation
Returns the path following translation PID config.- Returns:
- path translation PID config
-
getPathRotation
Returns the path following rotation PID config.- Returns:
- path rotation PID config
-
getShootingSpeedScale
public double getShootingSpeedScale()Reads the shooting speed scale as a fraction (0.0–1.0). A config value of 70 means the drive runs at 70% of max speed while shooting.- Returns:
- shooting speed scale factor between 0.0 and 1.0
-
getLowVoltageThresholdVolts
public double getLowVoltageThresholdVolts()Reads the battery voltage threshold below which low-voltage speed scaling activates.- Returns:
- low voltage threshold in volts
-
getLowVoltageSpeedScale
public double getLowVoltageSpeedScale()Reads the low-voltage speed scale as a fraction (0.0–1.0).- Returns:
- low-voltage speed scale factor between 0.0 and 1.0
-
getCriticalVoltageThresholdVolts
public double getCriticalVoltageThresholdVolts()Reads the battery voltage threshold below which critical-voltage speed scaling activates.- Returns:
- critical voltage threshold in volts
-
getCriticalVoltageSpeedScale
public double getCriticalVoltageSpeedScale()Reads the critical-voltage speed scale as a fraction (0.0–1.0).- Returns:
- critical-voltage speed scale factor between 0.0 and 1.0
-
isApplyPowerManagementInAuto
public boolean isApplyPowerManagementInAuto()Returns whether state-based power management applies during autonomous mode.- Returns:
- true when shooting speed scale should also apply during auto
-