Class Intake
java.lang.Object
org.edu_nation.easy_ftc.mechanism.Intake
Implements an intake by extending the functionality of
MotorMechanism- See Also:
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic classConstruct anIntakeobject using the builder design patternstatic enumDirections that can be passed tocommand(direction, measurement, power) -
Method Summary
Modifier and TypeMethodDescriptionvoidcommand(Intake.Direction direction, double measurement, double power) Initiate an automated intake movementvoidcontrol()Enable teleoperated intake movement with gamepad (dpadUp, dpadDown) at a power of 0.5voidcontrol(double power) Enable teleoperated intake movement with gamepad (dpadUp, dpadDown) at the specified power
-
Method Details
-
control
public void control(double power) Enable teleoperated intake movement with gamepad (dpadUp, dpadDown) at the specified power- Parameters:
power- fraction of total power/velocity to use for mechanism control- Throws:
IllegalArgumentException- if power is not in the interval (0, 1]
-
control
public void control()Enable teleoperated intake movement with gamepad (dpadUp, dpadDown) at a power of 0.5 -
command
Initiate an automated intake movement- Parameters:
direction- direction to move the mechanism; seeIntake.Directionfor accepted valuesmeasurement- time(s) or distance to move the mechanismpower- fraction of total power/velocity to use for mechanism command- Throws:
NullPointerException- if direction is nullIllegalArgumentException- if direction is an unexpected valueIllegalArgumentException- if measurement < 0IllegalArgumentException- if power is not in the interval (0, 1]
-