Index
All Classes and Interfaces|All Packages
A
- addConditional(Supplier<Boolean>, Runnable) - Method in class MRILib.statemachine.ArmFSM
-
Adds a conditional action to be checked once per loop.
- ArmBotEasy - Class in MRILib.managers
-
Extends the base
Bot
class to include specific hardware and control logic for a robot arm mechanism consisting of a slide, pivot, and claw assembly. - ArmBotEasy(HardwareMap) - Constructor for class MRILib.managers.ArmBotEasy
-
Constructor for ArmBotEasy.
- ArmBotFF - Class in MRILib.managers
-
Extends Bot to manage arm-specific hardware (motors, servos) for a Pivoting Slide Arm robot.
- ArmBotFF(HardwareMap, Telemetry) - Constructor for class MRILib.managers.ArmBotFF
-
Constructor: Initializes the ArmBotFF.
- armController - Variable in class MRILib.managers.ArmBotFF
-
Controller instance for managing pivot arm movements, potentially with feedforward.
- ArmFSM - Class in MRILib.statemachine
-
Finite State Machine for controlling robot arm mechanisms.
- ArmFSM(ArmBotEasy) - Constructor for class MRILib.statemachine.ArmFSM
-
Constructor for Autonomous usage (no gamepads needed).
- ArmFSM(ArmBotEasy, Gamepad, Gamepad) - Constructor for class MRILib.statemachine.ArmFSM
-
Constructor for TeleOp usage (includes gamepads).
- armThread - Variable in class MRILib.managers.ArmBotFF
-
Thread dedicated to running the armController logic concurrently.
- auton - Variable in class MRILib.statemachine.ArmFSM
-
Flag indicating if the FSM is running in Autonomous mode.
B
- backLeft - Variable in class MRILib.managers.Bot
- backLeftPos - Variable in class MRILib.managers.Bot
-
Current encoder position of the back left drive motor.
- backLeftPosPrev - Variable in class MRILib.managers.Bot
-
Previous encoder position of the back left drive motor (from the last
Bot.updateEncoders()
call). - backRight - Variable in class MRILib.managers.Bot
- backRightPos - Variable in class MRILib.managers.Bot
-
Current encoder position of the back right drive motor.
- backRightPosPrev - Variable in class MRILib.managers.Bot
-
Previous encoder position of the back right drive motor (from the last
Bot.updateEncoders()
call). - bot - Variable in class MRILib.motion.PIDController
-
The robot hardware interface (
Bot
or subclass) providing access to sensors and motors. - bot - Variable in class MRILib.statemachine.ArmFSM
-
The robot's arm hardware and methods manager.
- bot - Variable in class MRILib.statemachine.DriveFSM
-
The robot hardware and state manager.
- Bot - Class in MRILib.managers
-
Base Robot Hardware Manager and Controller
- Bot(HardwareMap) - Constructor for class MRILib.managers.Bot
-
Constructs a Bot instance, initializing drive motors, IMU, odometry, and voltage sensor.
- BotState - Class in MRILib.statemachine
-
Base class for states within a Finite State Machine (FSM).
- BotState() - Constructor for class MRILib.statemachine.BotState
-
Default constructor.
- BotState(String) - Constructor for class MRILib.statemachine.BotState
-
Constructor to create a state with a specific name.
C
- checkConditionals() - Method in class MRILib.statemachine.ArmFSM
-
Checks all stored conditionals.
- claw - Variable in class MRILib.managers.ArmBotEasy
- claw - Variable in class MRILib.managers.ArmBotFF
-
The servo controlling the claw grip.
- claw_pitch - Variable in class MRILib.managers.ArmBotEasy
- claw_pitch - Variable in class MRILib.managers.ArmBotFF
-
The servo controlling the pitch (up/down tilt) of the claw.
- claw_roll - Variable in class MRILib.managers.ArmBotEasy
- claw_roll - Variable in class MRILib.managers.ArmBotFF
-
The servo controlling the roll (side-to-side rotation) of the claw.
- conditionalList - Variable in class MRILib.statemachine.ArmFSM
-
List to hold conditional actions to be checked each loop.
- currentPosition - Variable in class MRILib.managers.Bot
- currentState - Variable in class MRILib.statemachine.ArmFSM
-
The currently active arm state.
- currentStep - Variable in class MRILib.statemachine.DriveFSM
-
Index of the currently active step in the 'steps' list.
D
- driveFieldXYW(double, double, double) - Method in class MRILib.managers.Bot
-
Drives the robot using field-centric Cartesian coordinates (x, y) and robot-centric rotation (w).
- DriveFSM - Class in MRILib.statemachine
-
Controls robot motion during autonomous using a finite state machine.
- DriveFSM(Bot, PIDController) - Constructor for class MRILib.statemachine.DriveFSM
-
Initializes the DriveFSM.
- driveXYW(double, double, double) - Method in class MRILib.managers.Bot
-
Drives the robot using robot-centric Cartesian coordinates (x, y) and rotation (w).
E
- enableBrakeMode(boolean) - Method in class MRILib.managers.Bot
-
Enables or disables the "brake" zero power behavior for all drive motors.
- end() - Method in class MRILib.statemachine.ArmFSM
-
Executes the end logic of the current state.
- end() - Method in class MRILib.statemachine.BotState
-
Called once when this state is about to be deactivated (e.g., before transitioning to another state).
- end() - Method in class MRILib.statemachine.DriveFSM
-
Executes the end logic of the current step.
- errorSum - Variable in class MRILib.motion.PID
-
The accumulated integral error sum.
- errorSumTotal - Variable in class MRILib.motion.PID
-
The maximum absolute value the integral error sum (
PID.errorSum
) is allowed to reach.
F
- frontLeft - Variable in class MRILib.managers.Bot
- frontLeftPos - Variable in class MRILib.managers.Bot
-
Current encoder position of the front left drive motor.
- frontLeftPosPrev - Variable in class MRILib.managers.Bot
-
Previous encoder position of the front left drive motor (from the last
Bot.updateEncoders()
call). - frontRight - Variable in class MRILib.managers.Bot
- frontRightPos - Variable in class MRILib.managers.Bot
-
Current encoder position of the front right drive motor.
- frontRightPosPrev - Variable in class MRILib.managers.Bot
-
Previous encoder position of the front right drive motor (from the last
Bot.updateEncoders()
call).
G
- getBL() - Method in class MRILib.managers.Bot
- getBLPos() - Method in class MRILib.managers.Bot
- getBLPosPrev() - Method in class MRILib.managers.Bot
- getBR() - Method in class MRILib.managers.Bot
- getBRPos() - Method in class MRILib.managers.Bot
- getBRPosPrev() - Method in class MRILib.managers.Bot
- getClaw() - Method in class MRILib.managers.ArmBotEasy
-
Gets the main claw grip servo instance.
- getClaw() - Method in class MRILib.managers.ArmBotFF
- getClawPitch() - Method in class MRILib.managers.ArmBotEasy
-
Gets the claw pitch servo instance.
- getClawPitch() - Method in class MRILib.managers.ArmBotFF
- getClawPitchPos() - Method in class MRILib.managers.ArmBotEasy
-
Gets the current commanded position of the claw pitch servo.
- getClawPitchPos() - Method in class MRILib.managers.ArmBotFF
- getClawPos() - Method in class MRILib.managers.ArmBotEasy
-
Gets the current commanded position of the main claw grip servo.
- getClawPos() - Method in class MRILib.managers.ArmBotFF
- getClawRoll() - Method in class MRILib.managers.ArmBotEasy
-
Gets the claw roll servo instance.
- getClawRoll() - Method in class MRILib.managers.ArmBotFF
- getClawRollPos() - Method in class MRILib.managers.ArmBotEasy
-
Gets the current commanded position of the claw roll servo.
- getClawRollPos() - Method in class MRILib.managers.ArmBotFF
- getCurrentDegrees() - Method in class MRILib.motion.PIDController
-
Gets the robot's current heading in degrees, based on odometry.
- getCurrentRadians() - Method in class MRILib.motion.PIDController
-
Gets the robot's current heading in radians, based on odometry.
- getFL() - Method in class MRILib.managers.Bot
- getFLPos() - Method in class MRILib.managers.Bot
- getFLPosPrev() - Method in class MRILib.managers.Bot
- getFR() - Method in class MRILib.managers.Bot
- getFRPos() - Method in class MRILib.managers.Bot
- getFRPosPrev() - Method in class MRILib.managers.Bot
- getHeading() - Method in class MRILib.managers.Bot
-
Gets the current estimated heading of the robot.
- getIMUHeading() - Method in class MRILib.managers.Bot
-
Gets the robot's current heading (yaw) from the IMU.
- getLastPosition() - Method in class MRILib.managers.Bot
-
Gets the robot's position and heading from the *previous* update cycle.
- getOdoPosition() - Method in class MRILib.managers.Bot
-
Gets the raw position directly from the GoBilda Pinpoint driver.
- getPivotMotor() - Method in class MRILib.managers.ArmBotEasy
-
Gets the pivot motor instance.
- getPivotMotor() - Method in class MRILib.managers.ArmBotFF
- getPivotPos() - Method in class MRILib.managers.ArmBotEasy
-
Gets the last updated encoder position of the pivot motor.
- getPivotPos() - Method in class MRILib.managers.ArmBotFF
- getPivotVelocity() - Method in class MRILib.managers.ArmBotFF
- getPosition() - Method in class MRILib.managers.Bot
-
Gets the robot's current position and heading as estimated by the odometry system.
- getSlideMotor() - Method in class MRILib.managers.ArmBotEasy
-
Gets the slide motor instance.
- getSlideMotor() - Method in class MRILib.managers.ArmBotFF
- getSlidePos() - Method in class MRILib.managers.ArmBotEasy
-
Gets the last updated encoder position of the slide motor.
- getSlidePos() - Method in class MRILib.managers.ArmBotFF
- getSlideVelocity() - Method in class MRILib.managers.ArmBotFF
- getTargetDegrees() - Method in class MRILib.motion.PIDController
-
Gets the current target heading in degrees.
- getTargetRadians() - Method in class MRILib.motion.PIDController
-
Gets the current target heading set by
moveTo(double, double, double)
. - getTargetX() - Method in class MRILib.motion.PIDController
-
Gets the current target X-coordinate set by
moveTo(double, double, double)
. - getTargetY() - Method in class MRILib.motion.PIDController
-
Gets the current target Y-coordinate set by
moveTo(double, double, double)
. - getVoltage() - Method in class MRILib.managers.Bot
-
Gets the current battery voltage reported by the first available voltage sensor.
- getX() - Method in class MRILib.managers.Bot
-
Gets the current estimated X-coordinate of the robot.
- getY() - Method in class MRILib.managers.Bot
-
Gets the current estimated Y-coordinate of the robot.
- gpad1 - Variable in class MRILib.statemachine.ArmFSM
-
Reference to gamepad 1 for TeleOp control.
- gpad2 - Variable in class MRILib.statemachine.ArmFSM
-
Reference to gamepad 2 for TeleOp control.
H
- HeadingPID - Class in MRILib.motion
-
Extends the standard
PID
controller specifically for controlling heading or angles. - HeadingPID(double, double, double) - Constructor for class MRILib.motion.HeadingPID
-
Constructs a new HeadingPID controller with specified gains.
I
- iLimit - Variable in class MRILib.motion.PID
-
Integral limit (I-Zone).
- imu - Variable in class MRILib.managers.Bot
-
The Control Hub/Expansion Hub IMU (Inertial Measurement Unit) instance.
- init() - Method in class MRILib.statemachine.ArmFSM
-
Initializes all the arm states.
- initIMU(HardwareMap) - Method in class MRILib.managers.Bot
-
Initializes the Control Hub's IMU using the default hardwareMap name ("imu").
- initIMU(HardwareMap, String) - Method in class MRILib.managers.Bot
-
Initializes the Control Hub's IMU with a specified hardwareMap name and orientation parameters defined in
invalid reference
BotValues
- initMotors(HardwareMap) - Method in class MRILib.managers.ArmBotEasy
-
Initializes the slide and pivot motors.
- initMotors(HardwareMap) - Method in class MRILib.managers.ArmBotFF
-
Initializes slide and pivot motors from the hardware map.
- initMotors(HardwareMap) - Method in class MRILib.managers.Bot
-
Initializes the drive motors using default hardwareMap names ("frontLeft", "frontRight", "backLeft", "backRight").
- initMotors(HardwareMap, String, String, String, String) - Method in class MRILib.managers.Bot
-
Initializes the drive motors with specified hardwareMap names and sets their directions.
- initOdo(HardwareMap) - Method in class MRILib.managers.Bot
-
Initializes the GoBilda Pinpoint Odometry Computer using the default hardwareMap name ("odo").
- initOdo(HardwareMap, String) - Method in class MRILib.managers.Bot
-
Initializes the GoBilda Pinpoint Odometry Computer with a specified hardwareMap name.
- initServos(HardwareMap) - Method in class MRILib.managers.ArmBotEasy
-
Initializes the claw, claw pitch, and claw roll servos.
- initServos(HardwareMap) - Method in class MRILib.managers.ArmBotFF
-
Initializes claw servos from the hardware map.
K
- kD - Variable in class MRILib.motion.PID
-
Derivative gain (kD).
- kI - Variable in class MRILib.motion.PID
-
Integral gain (kI).
- kP - Variable in class MRILib.motion.PID
-
Proportional gain (kP).
L
- lastAngle - Variable in class MRILib.statemachine.DriveFSM
-
Stores the last target heading for hold position.
- lastError - Variable in class MRILib.motion.PID
-
The error calculated during the previous
PID.update(double)
call, used for calculating the derivative term. - lastPosition - Variable in class MRILib.managers.Bot
- lastTime - Variable in class MRILib.motion.PID
-
Timestamp of the last
PID.update(double)
call, used for calculating delta time. - lastX - Variable in class MRILib.statemachine.DriveFSM
-
Stores the last target X coordinate for hold position.
- lastY - Variable in class MRILib.statemachine.DriveFSM
-
Stores the last target Y coordinate for hold position.
M
- maxAngSpeed - Variable in class MRILib.motion.PIDController
-
Supplier for the maximum allowable angular (rotational) speed component.
- maxSpeed - Variable in class MRILib.motion.PIDController
-
Supplier for the maximum allowable translational speed component.
- moveTo(double, double, double) - Method in class MRILib.motion.PIDController
-
Sets the target pose for the PID controllers.
- moveTo(double, double, double) - Method in class MRILib.statemachine.DriveFSM
-
Adds a moveTo step with default timeout and no parallel command.
- moveTo(double, double, double, double) - Method in class MRILib.statemachine.DriveFSM
-
Adds a moveTo step with a specific timeout and no parallel command.
- moveTo(double, double, double, Runnable) - Method in class MRILib.statemachine.DriveFSM
-
Adds a moveTo step with a parallel command and default timeout.
- moveTo(double, double, double, Runnable, double) - Method in class MRILib.statemachine.DriveFSM
-
Adds a state to move to a target pose, optionally running a command.
- moveTo(Pose2D) - Method in class MRILib.statemachine.DriveFSM
-
Adds a moveTo step using a Pose2D object with default timeout.
- MRILib.managers - package MRILib.managers
- MRILib.motion - package MRILib.motion
- MRILib.statemachine - package MRILib.statemachine
N
- name - Variable in class MRILib.statemachine.BotState
-
The name identifier for this state, used for debugging and retrieval.
- nextState - Variable in class MRILib.motion.PIDController
-
Flag, declared but apparently unused in the current implementation.
- nextState() - Method in class MRILib.statemachine.DriveFSM
-
Ends the current step and starts the next one.
O
P
- pid - Variable in class MRILib.statemachine.DriveFSM
-
The PID controller for movement.
- PID - Class in MRILib.motion
-
Implements a standard Proportional-Integral-Derivative (PID) controller.
- PID(double, double, double) - Constructor for class MRILib.motion.PID
-
Constructs a new PID controller with specified gains.
- PIDController - Class in MRILib.motion
-
Manages three independent
PID
controllers (for X, Y, and Theta/Heading) to guide a robot towards a targetinvalid reference
Pose2D
- PIDController(Bot, Telemetry) - Constructor for class MRILib.motion.PIDController
-
Constructs a PIDController associated with a generic
Bot
. - pivot - Variable in class MRILib.managers.ArmBotEasy
- pivot - Variable in class MRILib.managers.ArmBotFF
-
The motor controlling the arm pivot rotation.
- pivotPos - Variable in class MRILib.managers.ArmBotEasy
- pivotPos - Variable in class MRILib.managers.ArmBotFF
-
Current encoder position of the pivot motor.
- pivotPosPrev - Variable in class MRILib.managers.ArmBotEasy
- pivotPosPrev - Variable in class MRILib.managers.ArmBotFF
-
Previous encoder position of the pivot motor (from the last update).
- POWER_SCALE - Variable in class MRILib.motion.PIDController
-
Scaling factor for power, declared but currently unused.
R
- resetEncoders() - Method in class MRILib.managers.ArmBotEasy
-
Resets the encoders for all drive motors (via superclass) and the arm motors (slide, pivot).
- resetEncoders() - Method in class MRILib.managers.ArmBotFF
-
Resets encoders for drive motors (via superclass) and arm motors.
- resetEncoders() - Method in class MRILib.managers.Bot
-
Resets the drive motor encoders to 0 without changing their current
DcMotor.RunMode
. - resetIMUHeading() - Method in class MRILib.managers.Bot
-
Resets the IMU's yaw angle to zero based on the current orientation.
- resetPrevEncoders() - Method in class MRILib.managers.ArmBotFF
-
Resets the internal previous encoder position trackers for arm motors.
- resetPrevEncoders() - Method in class MRILib.managers.Bot
-
Resets the stored *previous* encoder tick values to zero.
- run(Runnable) - Method in class MRILib.statemachine.DriveFSM
-
Adds a step to run a command immediately (0-second wait).
S
- setArm(int, int) - Method in class MRILib.managers.ArmBotEasy
-
Convenience method to set both the pivot and slide motors to run to target positions simultaneously.
- setArm(int, int) - Method in class MRILib.managers.ArmBotFF
-
Sets both pivot and slide motors to run to target positions simultaneously.
- setArmMode(DcMotor.RunMode) - Method in class MRILib.managers.ArmBotEasy
-
Sets the
DcMotor.RunMode
for both the slide and pivot motors simultaneously. - setArmMode(DcMotor.RunMode) - Method in class MRILib.managers.ArmBotFF
-
Sets the
DcMotor.RunMode
for both slide and pivot motors. - setClaw(double) - Method in class MRILib.managers.ArmBotEasy
-
Sets the target position for the main claw grip servo.
- setClaw(double) - Method in class MRILib.managers.ArmBotFF
-
Sets the target position for the claw grip servo.
- setClawPitch(double) - Method in class MRILib.managers.ArmBotEasy
-
Sets the target position for the claw pitch servo.
- setClawPitch(double) - Method in class MRILib.managers.ArmBotFF
-
Sets the target position for the claw pitch servo.
- setClawRoll(double) - Method in class MRILib.managers.ArmBotEasy
-
Sets the target position for the claw roll servo.
- setClawRoll(double) - Method in class MRILib.managers.ArmBotFF
-
Sets the target position for the claw roll servo.
- setDirections() - Method in class MRILib.managers.Bot
-
Sets the direction of the drive motors based on the constants defined in
invalid reference
BotValues
- setILimit(double) - Method in class MRILib.motion.PID
-
Sets the integral limit (I-Zone).
- setIntegralSumLimit(double) - Method in class MRILib.motion.PID
-
Sets the clamping limit for the integral sum.
- setMaxAngSpeed(double) - Method in class MRILib.motion.PIDController
-
Sets the maximum angular (rotational) speed limit using a simple supplier.
- setMaxSpeed(double) - Method in class MRILib.motion.PIDController
-
Sets the maximum translational speed limit using a simple supplier.
- setMode(DcMotor.RunMode) - Method in class MRILib.managers.Bot
-
Sets the
DcMotor.RunMode
for all four drive motors simultaneously. - setPID(PID, PID) - Method in class MRILib.motion.PIDController
-
Sets the PID controllers for the X and Y axes (translational).
- setPivot(int) - Method in class MRILib.managers.ArmBotEasy
-
Sets the pivot motor to run to a specific target encoder position.
- setPivot(int) - Method in class MRILib.managers.ArmBotFF
-
Sets the pivot motor to run to a target encoder position.
- setPivotPower(double) - Method in class MRILib.managers.ArmBotFF
-
Sets the pivot motor power directly.
- setPosition(double, double, double) - Method in class MRILib.managers.Bot
-
Sets the robot's current position and heading in the odometry system.
- setPosition(Pose2D) - Method in class MRILib.managers.Bot
-
Overrides the current position tracked by the GoBilda Pinpoint Odometry Computer.
- setSlides(int) - Method in class MRILib.managers.ArmBotEasy
-
Sets the slide motor to run to a specific target encoder position.
- setSlides(int) - Method in class MRILib.managers.ArmBotFF
-
Sets the slide motor to run to a target encoder position.
- setState(String) - Method in class MRILib.statemachine.ArmFSM
-
Sets the current state by name.
- setState(ArmState) - Method in class MRILib.statemachine.ArmFSM
-
Sets the current state to the provided ArmState instance.
- setTarget(double) - Method in class MRILib.motion.PID
-
Sets the desired target value (setpoint) for the PID controller.
- setTurnPID(PID) - Method in class MRILib.motion.PIDController
-
Sets the PID controller for the Theta (heading/turn) axis.
- slide - Variable in class MRILib.managers.ArmBotEasy
- slide - Variable in class MRILib.managers.ArmBotFF
-
The motor controlling the linear slide extension.
- slidePos - Variable in class MRILib.managers.ArmBotEasy
- slidePos - Variable in class MRILib.managers.ArmBotFF
-
Current encoder position of the slide motor.
- slidePosPrev - Variable in class MRILib.managers.ArmBotEasy
- slidePosPrev - Variable in class MRILib.managers.ArmBotFF
-
Previous encoder position of the slide motor (from the last update).
- start() - Method in class MRILib.motion.PID
-
Resets the PID controller's internal state.
- start() - Method in class MRILib.motion.PIDController
-
Initializes the PID controllers.
- start() - Method in class MRILib.statemachine.ArmFSM
-
Executes the start logic of the current state.
- start() - Method in class MRILib.statemachine.BotState
-
Called once when this state becomes the active state in the FSM.
- start() - Method in class MRILib.statemachine.DriveFSM
-
Executes the start logic of the current step.
- steps - Variable in class MRILib.statemachine.DriveFSM
-
List of autonomous steps (states).
- stopMultiThread() - Method in class MRILib.managers.ArmBotFF
-
Stops the background arm controller thread safely.
T
- targetRadians - Variable in class MRILib.motion.PIDController
-
The current target heading (radians) set via
moveTo(double, double, double)
. - targetVal - Variable in class MRILib.motion.PID
-
The desired setpoint or target value for the controller.
- targetX - Variable in class MRILib.motion.PIDController
-
The current target X-coordinate (inches) set via
moveTo(double, double, double)
. - targetY - Variable in class MRILib.motion.PIDController
-
The current target Y-coordinate (inches) set via
moveTo(double, double, double)
. - telemetry - Variable in class MRILib.managers.Bot
- telemetry - Variable in class MRILib.motion.PIDController
-
Telemetry object for displaying debug information.
- thetaPID - Variable in class MRILib.motion.PIDController
-
The PID controller for the rotational (Theta/Heading) movement.
- timer - Variable in class MRILib.motion.PID
-
Timer used to calculate the time difference (deltaTime) between updates.
- timer - Variable in class MRILib.motion.PIDController
-
Timer object, declared but apparently unused in the current implementation.
- toString() - Method in class MRILib.statemachine.BotState
-
Provides a string representation of the state, which is its name.
- transition() - Method in class MRILib.statemachine.ArmFSM
-
Checks all transition conditions defined in the current state.
U
- update() - Method in class MRILib.managers.Bot
-
Updates the robot's state.
- update() - Method in class MRILib.motion.PIDController
-
Updates the PID controllers and commands the robot using field-centric drive.
- update() - Method in class MRILib.statemachine.ArmFSM
-
Executes the update logic of the current state and checks conditionals.
- update() - Method in class MRILib.statemachine.BotState
-
Called repeatedly in the FSM's update loop while this state is active.
- update() - Method in class MRILib.statemachine.DriveFSM
-
Executes the update logic of the current step.
- update(double) - Method in class MRILib.motion.HeadingPID
-
Updates the PID controller calculation specifically for angles/heading.
- update(double) - Method in class MRILib.motion.PID
-
Updates the PID controller calculation based on a single measured value.
- update(double, double) - Method in class MRILib.motion.PID
-
Updates the PID controller calculation by choosing between two measured values.
- updateControllerState() - Method in class MRILib.managers.ArmBotFF
-
Updates the arm controller with current pivot state.
- updateEncoders() - Method in class MRILib.managers.ArmBotEasy
-
Updates the stored encoder positions for all drive motors (via superclass) and the arm motors (slide, pivot).
- updateEncoders() - Method in class MRILib.managers.ArmBotFF
-
Updates current and previous encoder positions for drive and arm motors.
- updateEncoders() - Method in class MRILib.managers.Bot
-
Updates the stored encoder positions for the drive train motors.
V
- voltageSensor - Variable in class MRILib.managers.Bot
W
- waitForSeconds(double) - Method in class MRILib.statemachine.DriveFSM
-
Adds a wait step with no parallel command.
- waitForSeconds(double, Runnable) - Method in class MRILib.statemachine.DriveFSM
-
Adds a state to wait for a duration while holding position, optionally running a command.
X
- xPID - Variable in class MRILib.motion.PIDController
-
The PID controller for the X-axis movement (field-centric).
Y
- yPID - Variable in class MRILib.motion.PIDController
-
The PID controller for the Y-axis movement (field-centric).
All Classes and Interfaces|All Packages