Class ThreeWheeled.Builder

java.lang.Object
dev.narlyx.tweetybird.Odometers.ThreeWheeled.Builder
Enclosing class:
ThreeWheeled

public static class ThreeWheeled.Builder extends Object
Used to configure and start the odometer.
  • Constructor Details

    • Builder

      public Builder()
  • Method Details

    • setLeftEncoder

      public ThreeWheeled.Builder setLeftEncoder(com.qualcomm.robotcore.hardware.DcMotor leftEncoder)
      REQUIRED Defines the encoder on the left side of the robot.
      Parameters:
      leftEncoder - DCMotor reference to the encoder
      Returns:
      Updated builder
    • setFlipLeftEncoder

      public ThreeWheeled.Builder setFlipLeftEncoder(boolean flipLeftEncoder)
      OPTIONAL Reverses the direction of the left encoder if counting backwards, this encoder must be counting up when the bot is pushed forwards.
      Parameters:
      flipLeftEncoder - True to flip
      Returns:
      Updated builder
    • setRightEncoder

      public ThreeWheeled.Builder setRightEncoder(com.qualcomm.robotcore.hardware.DcMotor rightEncoder)
      REQUIRED Defines the encoder on the right side of the robot.
      Parameters:
      rightEncoder - DCMotor reference to the encoder
      Returns:
      Updated builder
    • setFlipRightEncoder

      public ThreeWheeled.Builder setFlipRightEncoder(boolean flipRightEncoder)
      OPTIONAL Reverses the direction of the right encoder if counting backwards, this encoder must be counting up when the bot is pushed forwards.
      Parameters:
      flipRightEncoder - True to flip
      Returns:
      Updated builder
    • setMiddleEncoder

      public ThreeWheeled.Builder setMiddleEncoder(com.qualcomm.robotcore.hardware.DcMotor middleEncoder)
      REQUIRED Defines the encoder in the middle of the bot.
      Parameters:
      middleEncoder - DCMotor reference to the encoder
      Returns:
      Updated builder
    • setFlipMiddleEncoder

      public ThreeWheeled.Builder setFlipMiddleEncoder(boolean flipMiddleEncoder)
      OPTIONAL Reverses the direction of the middle encoder if counting backwards, this encoder must be counting up when the bot is pushed to the right.
      Parameters:
      flipMiddleEncoder - True to flip
      Returns:
      Updated builder
    • setSideEncoderDistance

      public ThreeWheeled.Builder setSideEncoderDistance(double sideEncoderDistance)
      REQUIRED TO FUNCTION PROPERLY The distance between the left and right encoders.
      Parameters:
      sideEncoderDistance - Unit of measurement
      Returns:
      Updated builder
    • setMiddleEncoderOffset

      public ThreeWheeled.Builder setMiddleEncoderOffset(double middleEncoderOffset)
      REQUIRED TO FUNCTION PROPERLY The distance from the center of rotation to the middle encoder, if the encoder is to the front of the bot, then this value will be positive, this the encoder is to the back of the bot, this value will be negative.
      Parameters:
      middleEncoderOffset - Unit of measurement
      Returns:
      Updated builder
    • setEncoderWheelRadius

      public ThreeWheeled.Builder setEncoderWheelRadius(double encoderWheelRadius)
      REQUIRED TO FUNCTION PROPERLY The radius of the wheel attached to your encoder.
      Parameters:
      encoderWheelRadius - Unit of measurement
      Returns:
      Updated builder
    • setEncoderTicksPerRotation

      public ThreeWheeled.Builder setEncoderTicksPerRotation(double encoderTicksPerRotation)
      REQUIRED TO FUNCTION PROPERLY How many times your encoder will count during one full rotation (360 degrees), you can typically find this information on the manufacturers website.
      Parameters:
      encoderTicksPerRotation - Number of counts
      Returns:
      Updated builder
    • build

      public ThreeWheeled build()
      This will construct and return a new Odometer
      Returns:
      ThreeWheeled Odometer