Package yams.mechanisms.config
Class SwerveDriveConfig
java.lang.Object
yams.mechanisms.config.SwerveDriveConfig
Swerve Drive Configuration
-
Constructor Summary
ConstructorsConstructorDescriptionCreate theSwerveDriveConfigfor theSwerveDriveSwerveDriveConfig(Subsystem swerveSubsystem, SwerveModule... modules) Create theSwerveDriveConfigfor theSwerveDrive -
Method Summary
Modifier and TypeMethodDescriptionstatic Translation2dcubeTranslation(Translation2d translation) Cube theTranslation2dmagnitude given in Polar coordinates.Get the center of rotation.Get the gyro angle with inversions and offsets applied.Get the gyro offset.Get the starting pose of the robot.Get the maximum angular speed of the chassis.Get the maximum speed of the chassis.Get the maximum speed of the modules.Get theSwerveModules for theSwerveDrive.Get the rotation PID controller.Get the swerve drive subsystem.Get the telemetry verbosity for theSwerveModule.Get the translation PID controller.Optimize the given chassis speeds.static Translation2dscaleTranslation(Translation2d translation, double scalar) Scale theTranslation2dPolar coordinate magnitude.withCenterOfRotation(Translation2d centerOfRotation) Set the center of rotation; 0,0 is the center of the robot.withCenterOfRotation(Distance forward, Distance left) Set the center of rotation; 0,0 is the center of the robot.Set the discretization time for the pose estimation.Get theSwerveModules for theSwerveDrive.withGyroAngularVelocityScaleFactor(double scaleFactor) Set the angular velocity scale factor to improve the accuracy of the pose estimation.withGyroInverted(boolean inverted) Set the gyro inverted.withGyroOffset(Angle offset) Set the gyro offset.withGyroVelocity(Supplier<AngularVelocity> angularVelocitySupplier) Angular velocity of the gyro.withMaximumChassisSpeed(LinearVelocity speed, AngularVelocity angularVelocity) Maximum speed of the chassis to desaturate towards.Set the maximum speed of the modules to desaturate towards.withModules(SwerveModule... modules) Set theSwerveModules for theSwerveDrive.withRotationController(PIDController controller) Set the rotation PID controller.Set the discretization time for the pose estimation.withSimGyroAngularVelocityScaleFactor(double scaleFactor) Set the angular velocity scale factor to improve the accuracy of the pose estimation.withSimRotationController(PIDController controller) Set the rotation PID controller.withSimTranslationController(PIDController controller) Set the translation PID controller.withStartingPose(Pose2d pose) Set the starting pose of the robot.withSubsystem(Subsystem subsystem) Define aSubsystemfor theSwerveDrivewithTelemetry(SmartMotorControllerConfig.TelemetryVerbosity telemetryVerbosity) Configure telemetry for theSwerveModulemechanism.withTranslationController(PIDController controller) Set the translation PID controller.
-
Constructor Details
-
SwerveDriveConfig
Create theSwerveDriveConfigfor theSwerveDrive- Parameters:
modules-SwerveModules for theSwerveDriveswerveSubsystem- SwerveDrive subsystem.
-
SwerveDriveConfig
public SwerveDriveConfig()Create theSwerveDriveConfigfor theSwerveDrive- Implementation Note:
- Must define a Subsystem with
withSubsystem(Subsystem)and modules withwithModules(SwerveModule...)
-
-
Method Details
-
withSubsystem
Define aSubsystemfor theSwerveDrive- Parameters:
subsystem-Subsystemfor theSwerveDrive- Returns:
SwerveDriveConfigfor chaining.
-
withModules
Set theSwerveModules for theSwerveDrive.- Parameters:
modules-SwerveModules for theSwerveDrive.- Returns:
SwerveDriveConfigfor chaining.
-
withSimTranslationController
Set the translation PID controller.- Parameters:
controller-PIDControllerfor the translation, input units are meters.- Returns:
SwerveDriveConfigfor chaining.
-
withSimRotationController
Set the rotation PID controller.- Parameters:
controller-PIDControllerfor the rotation, input units are radians.- Returns:
SwerveDriveConfigfor chaining.
-
withTranslationController
Set the translation PID controller.- Parameters:
controller-PIDControllerfor the translation, input units are meters.- Returns:
SwerveDriveConfigfor chaining.
-
withRotationController
Set the rotation PID controller.- Parameters:
controller-PIDControllerfor the rotation, input units are radians.- Returns:
SwerveDriveConfigfor chaining.
-
withCenterOfRotation
Set the center of rotation; 0,0 is the center of the robot.- Parameters:
centerOfRotation-Translation2dof the center of rotation in Meters, X is forward, Y is left.- Returns:
SwerveDriveConfigfor chaining.
-
withCenterOfRotation
Set the center of rotation; 0,0 is the center of the robot.- Parameters:
forward- Forward distance from the center of robot.left- Left distance from the center of robot.- Returns:
SwerveDriveConfigfor chaining.
-
withSimDiscretizationTime
Set the discretization time for the pose estimation.- Parameters:
dt- Discretization time for the pose estimation.- Returns:
SwerveDriveConfigfor chaining.
-
withSimGyroAngularVelocityScaleFactor
Set the angular velocity scale factor to improve the accuracy of the pose estimation.- Parameters:
scaleFactor- Scale factor to apply to the gyro angular velocity, [0, 1].- Returns:
SwerveDriveConfigfor chaining.
-
withDiscretizationTime
Set the discretization time for the pose estimation.- Parameters:
dt- Discretization time for the pose estimation.- Returns:
SwerveDriveConfigfor chaining.
-
withGyroAngularVelocityScaleFactor
Set the angular velocity scale factor to improve the accuracy of the pose estimation.- Parameters:
scaleFactor- Scale factor to apply to the gyro angular velocity, [0, 1].- Returns:
SwerveDriveConfigfor chaining.
-
withGyroVelocity
Angular velocity of the gyro.- Parameters:
angularVelocitySupplier-Supplier<AngularVelocity>for the gyro angular velocity.- Returns:
SwerveDriveConfigfor chaining.
-
withGyro
Get theSwerveModules for theSwerveDrive.- Parameters:
gyro-Supplierfor the gyro.- Returns:
SwerveDriveConfigfor chaining.
-
withGyroOffset
Set the gyro offset.- Parameters:
offset- Offset to apply to the gyro.- Returns:
SwerveDriveConfigfor chaining.
-
withGyroInverted
Set the gyro inverted.- Parameters:
inverted- Inverted state of the gyro.- Returns:
SwerveDriveConfigfor chaining.
-
withMaximumChassisSpeed
public SwerveDriveConfig withMaximumChassisSpeed(LinearVelocity speed, AngularVelocity angularVelocity) Maximum speed of the chassis to desaturate towards.- Parameters:
speed- Linear velocity of the Chassis.angularVelocity- Angular velocity of the Chassis.- Returns:
SwerveDriveConfigfor chaining.
-
withMaximumModuleSpeed
Set the maximum speed of the modules to desaturate towards.- Parameters:
speed- Linear velocity of the modules.- Returns:
SwerveDriveConfigfor chaining.
-
withStartingPose
Set the starting pose of the robot.- Parameters:
pose-Pose2dto set the robot to.new Pose2d()- Returns:
SwerveDriveConfigfor chaining.
-
withTelemetry
public SwerveDriveConfig withTelemetry(SmartMotorControllerConfig.TelemetryVerbosity telemetryVerbosity) Configure telemetry for theSwerveModulemechanism.- Parameters:
telemetryVerbosity- Telemetry verbosity to apply.- Returns:
SwerveDriveConfigfor chaining.
-
getCenterOfRotation
Get the center of rotation.- Returns:
Translation2dof the center of rotation in Meters, X is forward, Y is left.
-
getTelemetryVerbosity
Get the telemetry verbosity for theSwerveModule.- Returns:
SmartMotorControllerConfig.TelemetryVerbosityfor theSwerveModule.
-
getModules
Get theSwerveModules for theSwerveDrive.- Returns:
SwerveModules for theSwerveDrive.
-
getGyroAngle
Get the gyro angle with inversions and offsets applied.- Returns:
Angleof the gyro.
-
getInitialPose
Get the starting pose of the robot.- Returns:
Pose2dof the robot.
-
getMaximumChassisLinearVelocity
Get the maximum speed of the chassis.- Returns:
- Maximum speed of the chassis.
-
getMaximumChassisAngularVelocity
Get the maximum angular speed of the chassis.- Returns:
- Maximum angular speed of the chassis.
-
getMaximumModuleLinearVelocity
Get the maximum speed of the modules.- Returns:
- Maximum speed of the modules.
-
optimizeRobotRelativeChassisSpeeds
Optimize the given chassis speeds.- Parameters:
speeds-ChassisSpeedsto optimize.- Returns:
- Optimized
ChassisSpeeds.
-
getGyroOffset
Get the gyro offset.- Returns:
- Gyro offset.
-
getTranslationPID
Get the translation PID controller.- Returns:
- Translation PID controller.
-
getRotationPID
Get the rotation PID controller.- Returns:
- Rotation PID controller.
-
cubeTranslation
Cube theTranslation2dmagnitude given in Polar coordinates.- Parameters:
translation-Translation2dto manipulate.- Returns:
- Cubed magnitude from
Translation2d.
-
scaleTranslation
Scale theTranslation2dPolar coordinate magnitude.- Parameters:
translation-Translation2dto use.scalar- Multiplier for the Polar coordinate magnitude to use.- Returns:
Translation2dscaled by given magnitude scalar.
-
getSubsystem
Get the swerve drive subsystem.- Returns:
- Swerve drive subsystem.
-