Class VelocityControlModule

  • All Implemented Interfaces:
    DriveModule

    public class VelocityControlModule
    extends java.lang.Object
    implements DriveModule
    A drivetrain module which will set the wheel velocity rather than percent power
    • Constructor Summary

      Constructors 
      Constructor Description
      VelocityControlModule​(edu.wpi.first.wpilibj.Encoder leftEncoder, edu.wpi.first.wpilibj.Encoder rightEncoder, double maxVelocity, double strength)
      Default constructor
      VelocityControlModule​(edu.wpi.first.wpilibj.Encoder leftEncoder, edu.wpi.first.wpilibj.Encoder rightEncoder, double maxVelocity, com.kylecorry.pid.PID velocityPID)
      Default constructor
    • Constructor Detail

      • VelocityControlModule

        public VelocityControlModule​(edu.wpi.first.wpilibj.Encoder leftEncoder,
                                     edu.wpi.first.wpilibj.Encoder rightEncoder,
                                     double maxVelocity,
                                     double strength)
        Default constructor
        Parameters:
        leftEncoder - the left encoder
        rightEncoder - the right encoder
        maxVelocity - the maximum velocity of the robot in the same units as the encoder's rate (something / second)
        strength - the velocity correction strength
      • VelocityControlModule

        public VelocityControlModule​(edu.wpi.first.wpilibj.Encoder leftEncoder,
                                     edu.wpi.first.wpilibj.Encoder rightEncoder,
                                     double maxVelocity,
                                     com.kylecorry.pid.PID velocityPID)
        Default constructor
        Parameters:
        leftEncoder - the left encoder
        rightEncoder - the right encoder
        maxVelocity - the maximum velocity of the robot in the same units as the encoder's rate (something / second)
        velocityPID - the PID to control velocity
    • Method Detail

      • run

        public DriveSpeed run​(DriveSpeed currentSpeed,
                              DriveSpeed desiredSpeed,
                              double deltaTime)
        Description copied from interface: DriveModule
        Run the drive module
        Specified by:
        run in interface DriveModule
        Parameters:
        currentSpeed - the current speed of the drivetrain
        desiredSpeed - the desired speed of the drivetrain
        deltaTime - the delta time since the last call in seconds
        Returns:
        the speed the drivetrain should set
      • setLeftEncoder

        public void setLeftEncoder​(edu.wpi.first.wpilibj.Encoder leftEncoder)
      • setRightEncoder

        public void setRightEncoder​(edu.wpi.first.wpilibj.Encoder rightEncoder)
      • setPID

        public void setPID​(com.kylecorry.pid.PID pid)
      • setMaxVelocity

        public void setMaxVelocity​(double maxVelocity)