Class TankDriveTrain
- java.lang.Object
-
- edu.wpi.first.wpilibj2.command.SubsystemBase
-
- io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
-
- io.github.frc5024.lib5k.bases.drivetrain.implementations.TankDriveTrain
-
- All Implemented Interfaces:
Sendable
,Subsystem
,IDifferentialDrivebase
,SafeSystem
,java.lang.AutoCloseable
- Direct Known Subclasses:
DualPIDTankDriveTrain
,OpenLoopTankDriveTrain
public abstract class TankDriveTrain extends AbstractDriveTrain
TankDriveTrain is an implementation of AbstractDriveTrain for tank-drive robots.
-
-
Nested Class Summary
-
Nested classes/interfaces inherited from class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
AbstractDriveTrain.State
-
-
Field Summary
Fields Modifier and Type Field Description protected double
maxSpeedPercent
-
Fields inherited from class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
logger, stateMachine
-
-
Constructor Summary
Constructors Constructor Description TankDriveTrain()
Create a new TankDriveTrain
-
Method Summary
All Methods Static Methods Instance Methods Abstract Methods Concrete Methods Modifier and Type Method Description static double
calculateThrottleCorrectionFactor(Rotation2d angularError)
Calculates a corrective factor for throttle values, as per: https://bitbucket.org/kaleb_dodd/simbot2019public/src/abc56f5220b5c94bca216f86e3b6b5757d0ffeff/src/main/java/frc/subsystems/Drive.java#lines-337void
enableConstantCurvature(boolean enabled)
Set if constant-curvature control should be usedChassis.Side
getFrontSide()
Get which side is the frontPose2d
getPose()
Get the robot's current poseTranslation2d
getVelocity()
Get the robot's velocity in meters per periodvoid
handleDriverInputs(double throttlePercent, double steeringPercent)
Handle inputs from a human operatorprotected void
handleOpenLoopControl(StateMetadata<AbstractDriveTrain.State> meta)
State handler for open-loop controlprotected abstract void
handleVoltage(double leftVolts, double rightVolts)
TO BE OVERRIDDEN BY THE USER.void
periodic()
void
reset()
Reset everythingprotected abstract void
resetEncoders()
TO BE OVERRIDDEN BY THE USER.void
resetPose(Pose2d pose)
Set a new pose for the robotprotected abstract void
setEncodersInverted(boolean encodersInverted)
TO BE OVERRIDDEN BY THE USER.void
setFrontSide(Chassis.Side side)
Set which side of the chassis is the "front".void
setMaxSpeedPercent(double maxSpeedPercent)
Set the maximum speed percentprotected abstract void
setMotorsInverted(boolean motorsInverted)
TO BE OVERRIDDEN BY THE USER.void
setOpenLoop(double leftVolts, double rightVolts)
Set an open-loop outputvoid
setOpenLoop(DifferentialVoltages voltages)
Set an open-loop outputvoid
stop()
Stop everything-
Methods inherited from class io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
close, createPathingCommand, createTurnCommand, enableBrakes, getCurrentHeading, getCurrentState, getSpeed, handleAutonomousRotation, handleDrivingToPose, handleGearShift, isAtGoal, runIteration, setGoalHeading, setGoalPose, setGoalPose, setRampRate
-
Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystem
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface io.github.frc5024.lib5k.hardware.common.drivebase.IDifferentialDrivebase
getLeftMeters, getRightMeters, getWidthMeters
-
Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
getCurrentCommand, getDefaultCommand, register, setDefaultCommand, simulationPeriodic
-
-
-
-
Method Detail
-
handleOpenLoopControl
protected void handleOpenLoopControl(StateMetadata<AbstractDriveTrain.State> meta)
Description copied from class:AbstractDriveTrain
State handler for open-loop control- Specified by:
handleOpenLoopControl
in classAbstractDriveTrain
- Parameters:
meta
- State metadata
-
handleVoltage
protected abstract void handleVoltage(double leftVolts, double rightVolts)
TO BE OVERRIDDEN BY THE USER. Send voltage to the motors- Parameters:
leftVolts
- Left side voltagerightVolts
- Right side voltage
-
resetEncoders
protected abstract void resetEncoders()
TO BE OVERRIDDEN BY THE USER. Reset the encoders to read 0 rotations each
-
setMotorsInverted
protected abstract void setMotorsInverted(boolean motorsInverted)
TO BE OVERRIDDEN BY THE USER. Set if the motor outputs should be inverted- Parameters:
motorsInverted
- Should invert motor outputs
-
setEncodersInverted
protected abstract void setEncodersInverted(boolean encodersInverted)
TO BE OVERRIDDEN BY THE USER. Set if the encoder inputs should be inverted- Parameters:
encodersInverted
- Should invert encoder inputs
-
periodic
public void periodic()
- Specified by:
periodic
in interfaceSubsystem
- Overrides:
periodic
in classAbstractDriveTrain
-
resetPose
public void resetPose(Pose2d pose)
Description copied from class:AbstractDriveTrain
Set a new pose for the robot- Specified by:
resetPose
in classAbstractDriveTrain
- Parameters:
pose
- New pose
-
getVelocity
public Translation2d getVelocity()
Description copied from class:AbstractDriveTrain
Get the robot's velocity in meters per period- Specified by:
getVelocity
in classAbstractDriveTrain
- Returns:
- Velocity
-
setFrontSide
public void setFrontSide(Chassis.Side side)
Description copied from class:AbstractDriveTrain
Set which side of the chassis is the "front". Used in autonomous path following- Specified by:
setFrontSide
in classAbstractDriveTrain
- Parameters:
side
- Which side is the new front
-
getFrontSide
public Chassis.Side getFrontSide()
Get which side is the front- Returns:
- Front side
-
handleDriverInputs
public void handleDriverInputs(double throttlePercent, double steeringPercent)
Handle inputs from a human operator- Parameters:
throttlePercent
- Throttle percentagesteeringPercent
- Steering percentage
-
setOpenLoop
public void setOpenLoop(double leftVolts, double rightVolts)
Set an open-loop output- Parameters:
leftVolts
- Left side voltagerightVolts
- Right side voltage
-
setOpenLoop
public void setOpenLoop(DifferentialVoltages voltages)
Set an open-loop output- Parameters:
voltages
- Voltages
-
enableConstantCurvature
public void enableConstantCurvature(boolean enabled)
Set if constant-curvature control should be used- Parameters:
enabled
- Should use constant-curvature control?
-
setMaxSpeedPercent
public void setMaxSpeedPercent(double maxSpeedPercent)
Description copied from class:AbstractDriveTrain
Set the maximum speed percent- Specified by:
setMaxSpeedPercent
in classAbstractDriveTrain
- Parameters:
maxSpeedPercent
- Maximum speed percent
-
getPose
public Pose2d getPose()
Description copied from class:AbstractDriveTrain
Get the robot's current pose- Specified by:
getPose
in classAbstractDriveTrain
- Returns:
- Current pose
-
stop
public void stop()
Description copied from interface:SafeSystem
Stop everything- Specified by:
stop
in interfaceSafeSystem
- Overrides:
stop
in classAbstractDriveTrain
-
reset
public void reset()
Description copied from interface:SafeSystem
Reset everything- Specified by:
reset
in interfaceSafeSystem
- Overrides:
reset
in classAbstractDriveTrain
-
calculateThrottleCorrectionFactor
public static double calculateThrottleCorrectionFactor(Rotation2d angularError)
Calculates a corrective factor for throttle values, as per: https://bitbucket.org/kaleb_dodd/simbot2019public/src/abc56f5220b5c94bca216f86e3b6b5757d0ffeff/src/main/java/frc/subsystems/Drive.java#lines-337- Parameters:
angularError
- Error from target heading- Returns:
- Throttle correction
-
-