Class Arm.Builder
java.lang.Object
org.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Arm.Builder>
org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Arm.Builder>
org.edu_nation.easy_ftc.mechanism.Arm.Builder
- Enclosing class:
Arm
public static class Arm.Builder
extends org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Arm.Builder>
Construct an
Arm object using the builder design pattern
Basic Usage:
Arm arm = new Arm.Builder(this, hardwareMap).build();
Defaults:
- reverse = false
- reverseDevices = {}
- gamepad = null
- encoder = false
- diameter = 0.0
- length = 0.0
- gearing = 0.0
- count = 1
- names = {"arm"}
- behavior = BRAKE
- dir1 = 0.0
- dir2 = 0.0
-
Constructor Summary
ConstructorsConstructorDescriptionBuilder(com.qualcomm.robotcore.eventloop.opmode.LinearOpMode opMode, com.qualcomm.robotcore.hardware.HardwareMap hardwareMap) Builder constructor -
Method Summary
Modifier and TypeMethodDescriptionbehavior(com.qualcomm.robotcore.hardware.DcMotor.ZeroPowerBehavior behavior) Specify the zero-power behavior of the motorsbuild()Build the armcount(int count) Specify the number of motorsdiameter(double diameter) Specify the diameter for encoder control (distance-based)down(double down) Specify the positional limit forDOWNencoder()Whether to enable encoders (time-based)gamepad(com.qualcomm.robotcore.hardware.Gamepad gamepad) Pass gamepad for teleop controlgearing(double gearing) Specify the gearing of the motors (increases accuracy of distance-based movement)length(double length) Specify the length for encoder control (distance-based)Change the names of the hardware devicesreverse()Whether to reverse devicesReverse the specified deviceReverse the specified devicesup(double up) Specify the positional limit forUPMethods inherited from class org.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder
deadzone, logo, usb
-
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 opModehardwareMap- instance of the calling opMode's hardwareMap- Throws:
NullPointerException- if opMode or hardwareMap are null
-
-
Method Details
-
reverse
Description copied from class:org.edu_nation.easy_ftc.mechanism.Mechanism.BuilderWhether to reverse devices- Overrides:
reversein classorg.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Arm.Builder>- Returns:
- builder instance
-
reverse
Description copied from class:org.edu_nation.easy_ftc.mechanism.Mechanism.BuilderReverse the specified device- Overrides:
reversein classorg.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Arm.Builder>- Parameters:
deviceName- name of the device to be reversed- Returns:
- builder instance
- Throws:
NullPointerException- if deviceName is null
-
reverse
Description copied from class:org.edu_nation.easy_ftc.mechanism.Mechanism.BuilderReverse the specified devices- Overrides:
reversein classorg.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Arm.Builder>- Parameters:
deviceNames- an array of the names of devices to be reversed- Returns:
- builder instance
- Throws:
NullPointerException- if deviceNames is null
-
gamepad
Description copied from class:org.edu_nation.easy_ftc.mechanism.Mechanism.BuilderPass gamepad for teleop control- Overrides:
gamepadin classorg.edu_nation.easy_ftc.mechanism.Mechanism.Builder<Arm.Builder>- Parameters:
gamepad- instance of the gamepad- Returns:
- builder instance
- Throws:
NullPointerException- if gamepad is null
-
encoder
Description copied from class:org.edu_nation.easy_ftc.mechanism.MotorMechanism.BuilderWhether to enable encoders (time-based)- Overrides:
encoderin classorg.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Arm.Builder>- Returns:
- builder instance
-
diameter
Description copied from class:org.edu_nation.easy_ftc.mechanism.MotorMechanism.BuilderSpecify the diameter for encoder control (distance-based)- Overrides:
diameterin classorg.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Arm.Builder>- Parameters:
diameter- measurement of the wheel or axel attached to the motor- Returns:
- builder instance
- Throws:
IllegalArgumentException- if diameter <= 0
-
length
Description copied from class:org.edu_nation.easy_ftc.mechanism.MotorMechanism.BuilderSpecify the length for encoder control (distance-based)- Overrides:
lengthin classorg.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Arm.Builder>- Parameters:
length- measurement of the length of the arm attached to the motor- Returns:
- builder instance
- Throws:
IllegalArgumentException- if length <= 0
-
gearing
Description copied from class:org.edu_nation.easy_ftc.mechanism.MotorMechanism.BuilderSpecify the gearing of the motors (increases accuracy of distance-based movement)- Overrides:
gearingin classorg.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Arm.Builder>- Parameters:
gearing- gearing of the motors in the mechanism- Returns:
- builder instance
- Throws:
IllegalArgumentException- if gearing <= 0
-
count
Specify the number of motors- Parameters:
count- the number of motors in the arm mechanism- Returns:
- builder instance
- Throws:
IllegalArgumentException- if count isn't 1 or 2
-
names
Change the names of the hardware devices- Specified by:
namesin classorg.edu_nation.easy_ftc.mechanism.MotorMechanism.Builder<Arm.Builder>- Parameters:
names- an array of the names for the hardware devices- Returns:
- builder instance
- Throws:
NullPointerException- if names is null
-
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
Specify the positional limit forUP- Parameters:
up- positional limit forUP- Returns:
- builder instance
-
down
Specify the positional limit forDOWN- Parameters:
down- positional limit forDOWN- Returns:
- builder instance
-
build
Build the arm- Returns:
- arm instance
- Throws:
IllegalStateException- if count != names.lengthIllegalStateException- if encoder = false and one of: diameter, length, or gearing has been setIllegalStateException- if dir1 < dir2
-