Class TurretSubsystemConfig
-
Nested Class Summary
Nested classes/interfaces inherited from class frc.robot.shared.config.AbstractConfig
AbstractConfig.ComponentPoseConfig -
Field Summary
FieldsModifier and TypeFieldDescription3D pivot offset for AdvantageScope component visualization.Field target positions and zone boundaries for zone-aware turret tracking.doublePosition error threshold for the on-target readiness check, in degrees.doubleLook-ahead time for rotational velocity compensation in seconds.doubleConvergence threshold for the Newton solver in seconds.doubleAerodynamic drag coefficient applied to the ball's inherited robot velocity during flight.booleanEnables or disables the shoot-on-the-move translational compensation.intMaximum Newton iterations before falling back to the uncompensated TOF.doubleRobot speed below which SOTM is disabled and the turret aims straight at the target.doubleZero offset between the turret's mechanical zero and robot-forward in degrees.Fields inherited from class frc.robot.shared.config.AbstractSetAndSeekSubsystemConfig
motionProfileFields inherited from class frc.robot.shared.config.AbstractMotorSubsystemConfig
feedforward, motorConfig, pid, sysIdFields inherited from class frc.robot.shared.config.AbstractSubsystemConfig
enabled, verbose -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptiondoubleReturns the on-target position tolerance for the turret readiness check.doubleReturns the rotational lead time used for yaw-rate compensation.doubleReturns the convergence tolerance for the SOTM Newton solver.doubleReturns the SOTM drag coefficient for inherited ball velocity decay during flight.intReturns the maximum Newton iterations for the SOTM solver.doubleReturns the minimum robot speed required to activate SOTM compensation.doubleReturns the turret zero offset in degrees.booleanReturns whether shoot-on-the-move translational compensation is enabled.Methods inherited from class frc.robot.shared.config.AbstractSetAndSeekSubsystemConfig
getMaximumSetpointDegrees, getMaximumSetpointRadians, getMinimumSetpointDegrees, getMinimumSetpointRadiansMethods 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
-
componentPoseConfig
3D pivot offset for AdvantageScope component visualization. -
fieldTargets
Field target positions and zone boundaries for zone-aware turret tracking. -
turretZeroOffsetDegrees
public double turretZeroOffsetDegreesZero offset between the turret's mechanical zero and robot-forward in degrees.A value of 180 means the turret faces the rear of the robot when at its mechanical zero position.
-
onTargetPositionToleranceDegrees
public double onTargetPositionToleranceDegreesPosition error threshold for the on-target readiness check, in degrees.This is typically wider than the profile's position tolerance and ignores velocity, so the turret can report "ready to shoot" while the profile is still making fine corrections.
-
rotationalLeadTimeSeconds
public double rotationalLeadTimeSecondsLook-ahead time for rotational velocity compensation in seconds.When the robot is spinning, the turret can lead its aim by this many seconds of predicted heading change to stay on target. Set to zero to disable compensation.
-
sotmEnabled
public boolean sotmEnabledEnables or disables the shoot-on-the-move translational compensation.When enabled, the turret aims at a virtual target that accounts for ball drift during flight due to robot velocity. Disable this at competition if the solver misbehaves.
-
sotmDragCoefficient
public double sotmDragCoefficientAerodynamic drag coefficient applied to the ball's inherited robot velocity during flight.A typical smooth sphere has a drag coefficient around 0.47. Higher values cause the ball's inherited velocity to decay faster, reducing the SOTM aim correction. Set to 0 to assume no drag (ball keeps full inherited velocity).
-
sotmMinSpeedMetersPerSecond
public double sotmMinSpeedMetersPerSecondRobot speed below which SOTM is disabled and the turret aims straight at the target.At very low speeds the ball drift is negligible. Setting this too low causes the solver to apply tiny corrections that add noise without improving accuracy.
-
sotmMaxIterations
public int sotmMaxIterationsMaximum Newton iterations before falling back to the uncompensated TOF. -
sotmConvergenceToleranceSeconds
public double sotmConvergenceToleranceSecondsConvergence threshold for the Newton solver in seconds.
-
-
Constructor Details
-
TurretSubsystemConfig
public TurretSubsystemConfig()
-
-
Method Details
-
getTurretZeroOffsetDegrees
public double getTurretZeroOffsetDegrees()Returns the turret zero offset in degrees.This offset is subtracted from the robot-relative target angle to convert into turret-relative coordinates. A value of 180 means turret mechanical zero points to the rear of the robot.
- Returns:
- turret zero offset in degrees
-
getOnTargetPositionToleranceDegrees
public double getOnTargetPositionToleranceDegrees()Returns the on-target position tolerance for the turret readiness check.- Returns:
- tolerance in degrees
-
getRotationalLeadTimeSeconds
public double getRotationalLeadTimeSeconds()Returns the rotational lead time used for yaw-rate compensation.The turret multiplies the robot's yaw rate by this value to predict how far the heading will change and pre-rotates accordingly. Tune this higher if the turret lags behind while the robot spins.
- Returns:
- lead time in seconds
-
isSotmEnabled
public boolean isSotmEnabled()Returns whether shoot-on-the-move translational compensation is enabled.- Returns:
- true when SOTM is active
-
getSotmDragCoefficient
public double getSotmDragCoefficient()Returns the SOTM drag coefficient for inherited ball velocity decay during flight.- Returns:
- drag coefficient (dimensionless, 0.47 for a smooth sphere)
-
getSotmMinSpeedMetersPerSecond
public double getSotmMinSpeedMetersPerSecond()Returns the minimum robot speed required to activate SOTM compensation.- Returns:
- speed threshold in meters per second
-
getSotmMaxIterations
public int getSotmMaxIterations()Returns the maximum Newton iterations for the SOTM solver.- Returns:
- maximum iteration count
-
getSotmConvergenceToleranceSeconds
public double getSotmConvergenceToleranceSeconds()Returns the convergence tolerance for the SOTM Newton solver.- Returns:
- tolerance in seconds
-