Class DriveTrainBase

  • All Implemented Interfaces:
    Sendable, Subsystem, IDifferentialDrivebase

    @Deprecated(since="October 2020",
                forRemoval=true)
    public abstract class DriveTrainBase
    extends SubsystemBase
    implements IDifferentialDrivebase
    Deprecated, for removal: This API element is subject to removal in a future version.
    The base for all drivetrains. This class is designed to reduce the amount of time spent actually making the robot move, and allowing anyone to easily write autonomous code by calling a single function.
    • Nested Class Summary

      Nested Classes 
      Modifier and Type Class Description
      static class  DriveTrainBase.States
      Deprecated, for removal: This API element is subject to removal in a future version.
       
    • Constructor Summary

      Constructors 
      Constructor Description
      DriveTrainBase​(DriveTrainConfig config)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Create a DriveTrainBase
    • Method Summary

      All Methods Instance Methods Abstract Methods Concrete Methods Deprecated Methods 
      Modifier and Type Method Description
      void becomeNeutral()
      Deprecated, for removal: This API element is subject to removal in a future version.
      This puts the drivetrain in "neutral mode".
      abstract void consumeOutputs​(DriveTrainOutput output)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Handle all outputs
      User must override this.
      PathFollowCommand createPathingCommand​(Path path, boolean inReverse, double lookaheadMeters, double epsRadius)
      Deprecated.
      PathFollowCommand createPathingCommand​(Path path, double epsRadius)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Create and configure a command that will follow a path using this drivetrain.
      abstract void customPeriodic()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Override this with your custom periodic code
      void drive​(double throttle, double turn, InputUtils.ScalingMode scaling)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Drive the robot with controller inputs
      void driveTo​(Translation2d goal, double epsilonMeters)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the robot to drive to a point smoothly.
      DriveTrainBase.States getInternalState()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Read the current state of the internal state machine.
      abstract double getLeftMeters()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the scalar distance traveled by the left side of the drivetrain
      Pose2d getPose()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the robot pose
      abstract double getRightMeters()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the scalar distance traveled by the right side of the drivetrain
      double getWidthMeters()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get track width in meters
      void holdPosition()
      Deprecated, for removal: This API element is subject to removal in a future version.
      This locks the drivetrain, and tells it to hold its position
      boolean isAtGoal()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Check if the drivetrain is currently done doing its task, and is sitting at it's goal.
      void periodic()
      Deprecated, for removal: This API element is subject to removal in a future version.
       
      abstract DriveTrainSensors readInputs()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get all sensor readings that the base needs
      User must override this.
      protected void runIteration()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Run a thread iteration
      void setActiveSide​(ChassisSide side)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set which side of the drivetrain to treat as the "front"
      void setGear​(Gear gear)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set what gearing the drivetrain should be using.
      void setPose​(Pose2d pose)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Force-set the drivetrain's pose
      void setSpeedCap​(double maxOutputPercent)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set a cap on the output speed by percentage
      void stop()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Stop everything
      void turnTo​(Rotation2d angle, Rotation2d epsilon, boolean relative)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Turn to an angle
      void turnTo​(Translation2d point, Rotation2d epsilon)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Turn to face a field-relative point
      void zero()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Zero all sensor readings (no-destructive to other subsystems)
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
    • Constructor Detail

      • DriveTrainBase

        public DriveTrainBase​(DriveTrainConfig config)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Create a DriveTrainBase
        Parameters:
        config - Configuration info
    • Method Detail

      • zero

        public void zero()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Zero all sensor readings (no-destructive to other subsystems)
      • stop

        public void stop()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Stop everything
      • periodic

        public void periodic()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Specified by:
        periodic in interface Subsystem
      • customPeriodic

        public abstract void customPeriodic()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Override this with your custom periodic code
      • runIteration

        protected void runIteration()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Run a thread iteration
      • drive

        public void drive​(double throttle,
                          double turn,
                          InputUtils.ScalingMode scaling)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Drive the robot with controller inputs
        Parameters:
        throttle - Throttle percentage [-1.0 to 1.0]
        turn - Turn percentage [-1.0 to 1.0]
        scaling - Scaling method
      • turnTo

        public void turnTo​(Rotation2d angle,
                           Rotation2d epsilon,
                           boolean relative)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Turn to an angle
        Parameters:
        angle - Angle to turn to
        epsilon - Allowed error
        relative - Is angle robot-relative?
      • turnTo

        public void turnTo​(Translation2d point,
                           Rotation2d epsilon)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Turn to face a field-relative point
        Parameters:
        point - Point on field
        epsilon - Allowed error
      • driveTo

        public void driveTo​(Translation2d goal,
                            double epsilonMeters)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Set the robot to drive to a point smoothly. This point can be modified while the robot is driving during path-following situations.
        Parameters:
        goal - Goal point in space (field-relative)
        epsilonMeters - Allowed radius from the point for the robot to stop
      • setGear

        public void setGear​(Gear gear)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Set what gearing the drivetrain should be using. This only works in open-loop mode!
        Parameters:
        gear - Desired gearing
      • createPathingCommand

        @Deprecated(since="August 2020",
                    forRemoval=false)
        public PathFollowCommand createPathingCommand​(Path path,
                                                      boolean inReverse,
                                                      double lookaheadMeters,
                                                      double epsRadius)
        Deprecated.
        Create and configure a command that will follow a path using this drivetrain
        Parameters:
        path - Path to follow
        inReverse - Should the path be followed in reverse?
        lookaheadMeters - How far to look ahead for new goal poses
        epsRadius - Radius around the final pose for trigger isFinished()
        Returns:
        Path following command
      • createPathingCommand

        public PathFollowCommand createPathingCommand​(Path path,
                                                      double epsRadius)
        Deprecated, for removal: This API element is subject to removal in a future version.
        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 follow
        epsRadius - Radius around the final pose for trigger isFinished()
        Returns:
        Path following command
      • readInputs

        public abstract DriveTrainSensors readInputs()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Get all sensor readings that the base needs
        User must override this.
        Returns:
        Sensor readings
      • consumeOutputs

        public abstract void consumeOutputs​(DriveTrainOutput output)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Handle all outputs
        User must override this.
        Parameters:
        output - Motor and config outputs
      • setActiveSide

        public void setActiveSide​(ChassisSide side)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Set which side of the drivetrain to treat as the "front"
        Parameters:
        side - Side to choose as active
      • getPose

        public Pose2d getPose()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Get the robot pose
        Returns:
        Pose
      • getInternalState

        public DriveTrainBase.States getInternalState()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Read the current state of the internal state machine. This should only really be used if you are writing a complex extension on top of this base.
        Returns:
        Internal state
      • isAtGoal

        public boolean isAtGoal()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Check if the drivetrain is currently done doing its task, and is sitting at it's goal. This can be used for calculating isFinished() methods for commands that rely on drivetrain positioning
        Returns:
        Is drivetrain at goal?
      • setPose

        public void setPose​(Pose2d pose)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Force-set the drivetrain's pose
        Parameters:
        pose - New pose
      • getLeftMeters

        public abstract double getLeftMeters()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Get the scalar distance traveled by the left side of the drivetrain
        Specified by:
        getLeftMeters in interface IDifferentialDrivebase
        Returns:
        left meters
      • getRightMeters

        public abstract double getRightMeters()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Get the scalar distance traveled by the right side of the drivetrain
        Specified by:
        getRightMeters in interface IDifferentialDrivebase
        Returns:
        right meters
      • getWidthMeters

        public double getWidthMeters()
        Deprecated, for removal: This API element is subject to removal in a future version.
        Description copied from interface: IDifferentialDrivebase
        Get track width in meters
        Specified by:
        getWidthMeters in interface IDifferentialDrivebase
        Returns:
        Track width
      • becomeNeutral

        public void becomeNeutral()
        Deprecated, for removal: This API element is subject to removal in a future version.
        This puts the drivetrain in "neutral mode". Allowing the robot to be pushed around, and no voltage is sent to the motors.
      • holdPosition

        public void holdPosition()
        Deprecated, for removal: This API element is subject to removal in a future version.
        This locks the drivetrain, and tells it to hold its position
      • setSpeedCap

        public void setSpeedCap​(double maxOutputPercent)
        Deprecated, for removal: This API element is subject to removal in a future version.
        Set a cap on the output speed by percentage
        Parameters:
        maxOutputPercent - Maximum percentage power output