Interface TunerConstants
- All Known Implementing Classes:
TunerConstants2023
,TunerConstants2025
public interface TunerConstants
Interface defining constants and configuration values for swerve drive tuning. This interface
provides access to module-specific configurations, drivetrain constants, and various control
parameters needed for swerve drive operation.
-
Method Summary
Modifier and TypeMethodDescriptioncom.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,
com.ctre.phoenix6.configs.TalonFXConfiguration, com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the back left swerve module.com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,
com.ctre.phoenix6.configs.TalonFXConfiguration, com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the back right swerve module.Gets the length of the robot with bumpers.Gets the width of the robot with bumpers.double
Gets the radius of the drive base from center to furthest module.Gets the PID controller for maintaining robot heading while driving.com.ctre.phoenix6.configs.Slot0Configs
Gets the PID gains for the drive motors.com.ctre.phoenix6.swerve.SwerveDrivetrainConstants
Gets the general drivetrain constants for the swerve drive.org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig
Gets the simulation config for Maple-Simcom.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,
com.ctre.phoenix6.configs.TalonFXConfiguration, com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the front left swerve module.com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,
com.ctre.phoenix6.configs.TalonFXConfiguration, com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the front right swerve module.com.pathplanner.lib.controllers.PPHolonomicDriveController
Gets the holonomic drive controller for path following.double
Gets the maximum rotational rate of individual modules.Gets the physical positions of all swerve modules relative to the robot center.Gets the robot's standard operating speed.double
Gets the frequency at which odometry updates are processed.com.pathplanner.lib.path.PathConstraints
Gets the constraints for PathPlanner pathfinding.com.pathplanner.lib.config.RobotConfig
Gets the PathPlanner configuration for the robot.double
Gets the radius in which precision align should functioncom.pathplanner.lib.controllers.PPHolonomicDriveController
Gets the precision align holonomic drive controller for path following.double
Gets the precision align tolerance (when it stops trying to correct)Gets the robot's maximum speed at 12 volts.com.ctre.phoenix6.configs.Slot0Configs
Gets the PID gains for the steer motors.Gets the robot's maximum boosted speed.Gets the robot's reduced speed for precision control.
-
Method Details
-
getFrontLeft
com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration, getFrontLeft()com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the front left swerve module.- Returns:
- SwerveModuleConstants containing TalonFX and CANcoder configurations for the front left module
-
getFrontRight
com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration, getFrontRight()com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the front right swerve module.- Returns:
- SwerveModuleConstants containing TalonFX and CANcoder configurations for the front right module
-
getBackLeft
com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration, getBackLeft()com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the back left swerve module.- Returns:
- SwerveModuleConstants containing TalonFX and CANcoder configurations for the back left module
-
getBackRight
com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration, getBackRight()com.ctre.phoenix6.configs.CANcoderConfiguration> Gets the configuration constants for the back right swerve module.- Returns:
- SwerveModuleConstants containing TalonFX and CANcoder configurations for the back right module
-
getDrivetrainConstants
com.ctre.phoenix6.swerve.SwerveDrivetrainConstants getDrivetrainConstants()Gets the general drivetrain constants for the swerve drive.- Returns:
- SwerveDrivetrainConstants containing overall drivetrain configuration
-
getDriveBaseRadius
double getDriveBaseRadius()Gets the radius of the drive base from center to furthest module.- Returns:
- The drive base radius in meters
-
getSpeedAt12Volts
LinearVelocity getSpeedAt12Volts()Gets the robot's maximum speed at 12 volts.- Returns:
- The maximum speed as a LinearVelocity
-
getTurtleSpeed
LinearVelocity getTurtleSpeed()Gets the robot's reduced speed for precision control.- Returns:
- The turtle mode speed as a LinearVelocity
-
getNominalSpeed
LinearVelocity getNominalSpeed()Gets the robot's standard operating speed.- Returns:
- The nominal speed as a LinearVelocity
-
getTurboSpeed
LinearVelocity getTurboSpeed()Gets the robot's maximum boosted speed.- Returns:
- The turbo mode speed as a LinearVelocity
-
getMaxModularRotationalRate
double getMaxModularRotationalRate()Gets the maximum rotational rate of individual modules.- Returns:
- The maximum rotational rate in radians per second
-
getOdometryFrequency
double getOdometryFrequency()Gets the frequency at which odometry updates are processed.- Returns:
- The odometry update frequency in hertz
-
getBumperLength
Distance getBumperLength()Gets the length of the robot with bumpers.- Returns:
- The bumper length as a Distance
-
getBumperWidth
Distance getBumperWidth()Gets the width of the robot with bumpers.- Returns:
- The bumper width as a Distance
-
getPathPlannerConfig
com.pathplanner.lib.config.RobotConfig getPathPlannerConfig()Gets the PathPlanner configuration for the robot.- Returns:
- RobotConfig containing PathPlanner-specific settings
-
getPathfindingConstraints
com.pathplanner.lib.path.PathConstraints getPathfindingConstraints()Gets the constraints for PathPlanner pathfinding.- Returns:
- PathConstraints containing velocity and acceleration limits
-
getHolonomicDriveController
com.pathplanner.lib.controllers.PPHolonomicDriveController getHolonomicDriveController()Gets the holonomic drive controller for path following.- Returns:
- PPHolonomicDriveController for path following control
-
getPrecisionAlignHolonomicDriveController
com.pathplanner.lib.controllers.PPHolonomicDriveController getPrecisionAlignHolonomicDriveController()Gets the precision align holonomic drive controller for path following.- Returns:
- PPHolonomicDriveController for path following control
-
getSteerGains
com.ctre.phoenix6.configs.Slot0Configs getSteerGains()Gets the PID gains for the steer motors.- Returns:
- Slot0Configs containing PID and feedforward gains for steering
-
getDriveGains
com.ctre.phoenix6.configs.Slot0Configs getDriveGains()Gets the PID gains for the drive motors.- Returns:
- Slot0Configs containing PID and feedforward gains for driving
-
getModuleTranslations
Translation2d[] getModuleTranslations()Gets the physical positions of all swerve modules relative to the robot center.- Returns:
- Array of Translation2d representing module positions
-
getDriveFacingAnglePIDController
ProfiledPIDController getDriveFacingAnglePIDController()Gets the PID controller for maintaining robot heading while driving.- Returns:
- ProfiledPIDController for heading control
-
getPrecisionAlignTolerance
double getPrecisionAlignTolerance()Gets the precision align tolerance (when it stops trying to correct)- Returns:
- double of tolerance
-
getPrecisionAlignAllowRadius
double getPrecisionAlignAllowRadius()Gets the radius in which precision align should function- Returns:
- double of tolerance
-
getDriveTrainSimulationConfig
org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig getDriveTrainSimulationConfig()Gets the simulation config for Maple-Sim- Returns:
- The simulation config
-