Class Lift.Builder

java.lang.Object
org.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Lift.Builder>
org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Lift.Builder>
org.edu_nation.easy_ftc.mechanism.Lift.Builder
Enclosing class:
Lift

public static class Lift.Builder extends org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Lift.Builder>
Construct a Lift object using the builder design pattern

Basic Usage:


 Lift lift = new Lift.Builder(this, hardwareMap).build();
 
Defaults:
  • reverse = false
  • reverseDevices = {}
  • gamepad = null
  • encoder = false
  • diameter = 0.0
  • gearing = 0.0
  • deadzone = 0.0
  • count = 1
  • names = {"lift"}
  • behavior = FLOAT
  • dir1 = 0.0
  • dir2 = 0.0
  • Constructor Details

    • Builder

      public Builder(com.qualcomm.robotcore.eventloop.opmode.LinearOpMode opMode, com.qualcomm.robotcore.hardware.HardwareMap hardwareMap)
      Builder constructor
      Parameters:
      opMode - instance of the calling opMode
      hardwareMap - instance of the calling opMode's hardwareMap
      Throws:
      NullPointerException - if opMode or hardwareMap are null
  • Method Details

    • reverse

      public Lift.Builder reverse()
      Description copied from class: org.edu_nation.easy_ftc.mechanism.Mechanism.Builder
      Whether to reverse devices
      Overrides:
      reverse in class org.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Lift.Builder>
      Returns:
      builder instance
    • reverse

      public Lift.Builder reverse(String deviceName)
      Description copied from class: org.edu_nation.easy_ftc.mechanism.Mechanism.Builder
      Reverse the specified device
      Overrides:
      reverse in class org.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Lift.Builder>
      Parameters:
      deviceName - name of the device to be reversed
      Returns:
      builder instance
      Throws:
      NullPointerException - if deviceName is null
    • reverse

      public Lift.Builder reverse(String[] deviceNames)
      Description copied from class: org.edu_nation.easy_ftc.mechanism.Mechanism.Builder
      Reverse the specified devices
      Overrides:
      reverse in class org.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Lift.Builder>
      Parameters:
      deviceNames - an array of the names of devices to be reversed
      Returns:
      builder instance
      Throws:
      NullPointerException - if deviceNames is null
    • gamepad

      public Lift.Builder gamepad(com.qualcomm.robotcore.hardware.Gamepad gamepad)
      Description copied from class: org.edu_nation.easy_ftc.mechanism.Mechanism.Builder
      Pass gamepad for teleop control
      Overrides:
      gamepad in class org.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Lift.Builder>
      Parameters:
      gamepad - instance of the gamepad
      Returns:
      builder instance
      Throws:
      NullPointerException - if gamepad is null
    • encoder

      public Lift.Builder encoder()
      Description copied from class: org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder
      Whether to enable encoders (time-based)
      Overrides:
      encoder in class org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Lift.Builder>
      Returns:
      builder instance
    • diameter

      public Lift.Builder diameter(double diameter)
      Description copied from class: org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder
      Specify the diameter for encoder control (distance-based)
      Overrides:
      diameter in class org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Lift.Builder>
      Parameters:
      diameter - measurement of the wheel or axel attached to the motor
      Returns:
      builder instance
      Throws:
      IllegalArgumentException - if diameter <= 0
    • gearing

      public Lift.Builder gearing(double gearing)
      Description copied from class: org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder
      Specify the gearing of the motors (increases accuracy of distance-based movement)
      Overrides:
      gearing in class org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Lift.Builder>
      Parameters:
      gearing - gearing of the motors in the mechanism
      Returns:
      builder instance
      Throws:
      IllegalArgumentException - if gearing <= 0
    • deadzone

      public Lift.Builder deadzone(double deadzone)
      Description copied from class: org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder
      Specify the joystick deadzone
      Overrides:
      deadzone in class org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Lift.Builder>
      Parameters:
      deadzone - minimum joystick/trigger value registered as input
      Returns:
      builder instance
      Throws:
      IllegalArgumentException - if deadzone < 0
    • count

      public Lift.Builder count(int count)
      Specify the number of motors
      Parameters:
      count - the number of motors in the lift mechanism
      Returns:
      builder instance
      Throws:
      IllegalArgumentException - if count isn't 1 or 2
    • names

      public Lift.Builder names(String[] names)
      Change the names of the hardware devices
      Specified by:
      names in class org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Lift.Builder>
      Parameters:
      names - an array of the names for the hardware devices
      Returns:
      builder instance
      Throws:
      NullPointerException - if names is null
    • behavior

      public Lift.Builder behavior(com.qualcomm.robotcore.hardware.DcMotor.ZeroPowerBehavior behavior)
      Specify the zero-power behavior of the motors
      Parameters:
      behavior - the zero-power behavior, one of ZeroPowerBehavior.BRAKE or FLOAT
      Returns:
      builder instance
      Throws:
      NullPointerException - if behavior is null
    • up

      public Lift.Builder up(double up)
      Specify the positional limit for UP
      Parameters:
      up - positional limit for UP
      Returns:
      builder instance
    • down

      public Lift.Builder down(double down)
      Specify the positional limit for DOWN
      Parameters:
      down - positional limit for DOWN
      Returns:
      builder instance
    • build

      public Lift build()
      Build the lift
      Returns:
      lift instance
      Throws:
      IllegalStateException - if count != names.length
      IllegalStateException - if encoder = false and one of: diameter, length, or gearing has been set
      IllegalStateException - if dir1 < dir2