Class DifferentialDrivetrain

  • All Implemented Interfaces:
    edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj2.command.Subsystem

    public class DifferentialDrivetrain
    extends LightningDrivetrain
    • Constructor Summary

      Constructors 
      Constructor Description
      DifferentialDrivetrain​(DifferentialGains gains, edu.wpi.first.wpilibj.motorcontrol.MotorController[] leftMotors, edu.wpi.first.wpilibj.motorcontrol.MotorController[] rightMotors, LightningIMU IMU, java.util.function.DoubleSupplier leftVelocity, java.util.function.DoubleSupplier rightVelocity, java.util.function.DoubleSupplier leftDistance, java.util.function.DoubleSupplier rightDistance)  
    • Constructor Detail

      • DifferentialDrivetrain

        public DifferentialDrivetrain​(DifferentialGains gains,
                                      edu.wpi.first.wpilibj.motorcontrol.MotorController[] leftMotors,
                                      edu.wpi.first.wpilibj.motorcontrol.MotorController[] rightMotors,
                                      LightningIMU IMU,
                                      java.util.function.DoubleSupplier leftVelocity,
                                      java.util.function.DoubleSupplier rightVelocity,
                                      java.util.function.DoubleSupplier leftDistance,
                                      java.util.function.DoubleSupplier rightDistance)
    • Method Detail

      • periodic

        public void periodic()
      • resetPose

        public void resetPose()
      • getDrivePIDFController

        public PIDFController getDrivePIDFController()
      • arcadeDrive

        public void arcadeDrive​(double speed,
                                double rot)
      • tankDrive

        public void tankDrive​(double leftPWR,
                              double rightPWR)
      • setVoltage

        public void setVoltage​(double leftVoltage,
                               double rightVoltage)
      • setLeftOutput

        protected void setLeftOutput​(double output)
      • setRightOutput

        protected void setRightOutput​(double output)
      • withEachMotor

        protected void withEachMotor​(java.util.function.Consumer<edu.wpi.first.wpilibj.motorcontrol.MotorController> op)
      • withEachLeftMotor

        protected void withEachLeftMotor​(java.util.function.Consumer<edu.wpi.first.wpilibj.motorcontrol.MotorController> op)
      • withEachRightMotor

        protected void withEachRightMotor​(java.util.function.Consumer<edu.wpi.first.wpilibj.motorcontrol.MotorController> op)
      • withEachMotorIndexed

        protected void withEachMotorIndexed​(java.util.function.BiConsumer<edu.wpi.first.wpilibj.motorcontrol.MotorController,​java.lang.Integer> op)
      • withEachMotor

        protected void withEachMotor​(java.util.function.BiConsumer<edu.wpi.first.wpilibj.motorcontrol.MotorController,​edu.wpi.first.wpilibj.motorcontrol.MotorController> op)