Class AbstractDriveTrain
- java.lang.Object
-
- edu.wpi.first.wpilibj2.command.SubsystemBase
-
- io.github.frc5024.lib5k.bases.drivetrain.AbstractDriveTrain
-
- All Implemented Interfaces:
Sendable
,Subsystem
,IDifferentialDrivebase
,SafeSystem
,java.lang.AutoCloseable
- Direct Known Subclasses:
TankDriveTrain
public abstract class AbstractDriveTrain extends SubsystemBase implements IDifferentialDrivebase, SafeSystem, java.lang.AutoCloseable
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description protected static class
AbstractDriveTrain.State
-
Field Summary
Fields Modifier and Type Field Description protected RobotLogger
logger
protected StateMachine<AbstractDriveTrain.State>
stateMachine
-
Constructor Summary
Constructors Constructor Description AbstractDriveTrain()
Create an AbstractDriveTrain
-
Method Summary
All Methods Instance Methods Abstract Methods Concrete Methods Modifier and Type Method Description void
close()
PathFollowerCommand
createPathingCommand(Path path, double epsRadius)
Create and configure a command that will follow a path using this drivetrain.TurnToCommand
createTurnCommand(Rotation2d heading, Rotation2d epsilon, double maxSpeedPercent, boolean fieldRelative)
Create a new TurnToCommand for this drivetrain.protected abstract void
enableBrakes(boolean enabled)
TO BE OVERRIDDEN BY THE USER.protected abstract Rotation2d
getCurrentHeading()
TO BE OVERRIDDEN BY THE USER.AbstractDriveTrain.State
getCurrentState()
Get the internal state of the DriveTrainabstract Pose2d
getPose()
Get the robot's current posedouble
getSpeed()
Get the robot's speed in meters per periodabstract Translation2d
getVelocity()
Get the robot's velocity in meters per periodprotected abstract void
handleAutonomousRotation(StateMetadata<AbstractDriveTrain.State> meta, Rotation2d goalHeading, Rotation2d epsilon)
State handler for autonomous rotation controlprotected abstract void
handleDrivingToPose(StateMetadata<AbstractDriveTrain.State> meta, Translation2d goalPose, Translation2d epsilon)
State handler for driving to a new pose autonomouslyprotected abstract void
handleGearShift(Gear gear)
TO BE OVERRIDDEN BY THE USER.protected abstract void
handleOpenLoopControl(StateMetadata<AbstractDriveTrain.State> meta)
State handler for open-loop controlboolean
isAtGoal()
Check if the drivetrain is currently at its goalvoid
periodic()
void
reset()
Reset everythingabstract void
resetPose(Pose2d pose)
Set a new pose for the robotprotected abstract void
runIteration()
TO BE OVERRIDDEN BY THE USER.abstract void
setFrontSide(Chassis.Side side)
Set which side of the chassis is the "front".void
setGoalHeading(Rotation2d heading, Rotation2d epsilon)
Set a field-relative heading for the robot to face, and immediately start facing it.void
setGoalPose(Pose2d pose, Translation2d epsilon)
Set a goal pose for the robot to be at, and immediately start driving to it.void
setGoalPose(Translation2d pose, Translation2d epsilon)
Set a goal pose for the robot to be at, and immediately start driving to it.abstract void
setMaxSpeedPercent(double maxSpeedPercent)
Set the maximum speed percentabstract void
setRampRate(double rampTimeSeconds)
TO BE OVERRIDDEN BY THE USER.void
stop()
Stop everything-
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
-
-
-
-
Field Detail
-
logger
protected RobotLogger logger
-
stateMachine
protected StateMachine<AbstractDriveTrain.State> stateMachine
-
-
Method Detail
-
handleGearShift
protected abstract void handleGearShift(Gear gear)
TO BE OVERRIDDEN BY THE USER. Handler for gear shifting- Parameters:
gear
- Gear to shift to
-
enableBrakes
protected abstract void enableBrakes(boolean enabled)
TO BE OVERRIDDEN BY THE USER. Handler for enabling the brakes.- Parameters:
enabled
- Should brakes be enabled?
-
getCurrentHeading
protected abstract Rotation2d getCurrentHeading()
TO BE OVERRIDDEN BY THE USER. Getter for the robot's current heading. Clockwise-positive- Returns:
- Robot's heading
-
runIteration
protected abstract void runIteration()
TO BE OVERRIDDEN BY THE USER. Any extra code that needs to be run every loop should go here.
-
setRampRate
public abstract void setRampRate(double rampTimeSeconds)
TO BE OVERRIDDEN BY THE USER. Handler for ramp rate setting- Parameters:
rampTimeSeconds
- Ramp rate time in seconds
-
setFrontSide
public abstract void setFrontSide(Chassis.Side side)
Set which side of the chassis is the "front". Used in autonomous path following- Parameters:
side
- Which side is the new front
-
getPose
public abstract Pose2d getPose()
Get the robot's current pose- Returns:
- Current pose
-
resetPose
public abstract void resetPose(Pose2d pose)
Set a new pose for the robot- Parameters:
pose
- New pose
-
getVelocity
public abstract Translation2d getVelocity()
Get the robot's velocity in meters per period- Returns:
- Velocity
-
getSpeed
public double getSpeed()
Get the robot's speed in meters per period- Returns:
- Robot speed
-
handleOpenLoopControl
protected abstract void handleOpenLoopControl(StateMetadata<AbstractDriveTrain.State> meta)
State handler for open-loop control- Parameters:
meta
- State metadata
-
setMaxSpeedPercent
public abstract void setMaxSpeedPercent(double maxSpeedPercent)
Set the maximum speed percent- Parameters:
maxSpeedPercent
- Maximum speed percent
-
handleAutonomousRotation
protected abstract void handleAutonomousRotation(StateMetadata<AbstractDriveTrain.State> meta, Rotation2d goalHeading, Rotation2d epsilon)
State handler for autonomous rotation control- Parameters:
meta
- State metadatagoalHeading
- Goal headingepsilon
- Rotation epsilon
-
handleDrivingToPose
protected abstract void handleDrivingToPose(StateMetadata<AbstractDriveTrain.State> meta, Translation2d goalPose, Translation2d epsilon)
State handler for driving to a new pose autonomously- Parameters:
meta
- State metadatagoalPose
- Goal poseepsilon
- Epsilon around the goal pose in meters
-
setGoalPose
public void setGoalPose(Pose2d pose, Translation2d epsilon)
Set a goal pose for the robot to be at, and immediately start driving to it.- Parameters:
pose
- Field-relative poseepsilon
- Pose epsilon in meters
-
setGoalPose
public void setGoalPose(Translation2d pose, Translation2d epsilon)
Set a goal pose for the robot to be at, and immediately start driving to it.- Parameters:
pose
- Field-relative poseepsilon
- Pose epsilon in meters
-
setGoalHeading
public void setGoalHeading(Rotation2d heading, Rotation2d epsilon)
Set a field-relative heading for the robot to face, and immediately start facing it.- Parameters:
heading
- Field-relative heading goalepsilon
- Heading epsilon
-
createPathingCommand
public PathFollowerCommand createPathingCommand(Path path, double epsRadius)
Create and configure a command that will follow a path using this drivetrain. This returns a builder-style object, where you can chain extra methods to configure the command- Parameters:
path
- Path to followepsRadius
- Radius in meters around the final pose for trigger isFinished()- Returns:
- Path following command
-
createTurnCommand
public TurnToCommand createTurnCommand(Rotation2d heading, Rotation2d epsilon, double maxSpeedPercent, boolean fieldRelative)
Create a new TurnToCommand for this drivetrain.- Parameters:
heading
- Desired headingepsilon
- Rotational epsilonmaxSpeedPercent
- Maximum speed as a percentfieldRelative
- Is the desired heading field-relative?- Returns:
- Generated TurnToCommand object
-
getCurrentState
public AbstractDriveTrain.State getCurrentState()
Get the internal state of the DriveTrain- Returns:
- Current internal state
-
isAtGoal
public boolean isAtGoal()
Check if the drivetrain is currently at its goal- Returns:
- Is currently at goal
-
stop
public void stop()
Description copied from interface:SafeSystem
Stop everything- Specified by:
stop
in interfaceSafeSystem
-
reset
public void reset()
Description copied from interface:SafeSystem
Reset everything- Specified by:
reset
in interfaceSafeSystem
-
close
public void close() throws java.lang.Exception
- Specified by:
close
in interfacejava.lang.AutoCloseable
- Throws:
java.lang.Exception
-
-