Skip navigation links
A B C D E F G H I J K L M N O P Q R S T U V W X Y 

A

accelerate(double[], double, double, double, double) - Method in class com.arcrobotics.ftclib.purepursuit.PathMotionProfile
Accelerates the motor speeds.
accelerationMetersPerSecondSq - Variable in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
ACHIEVABLE_MAX_TICKS_PER_SECOND - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
The achievable ticks per second velocity of the motor
actionPerformed() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
Returns true if the action has already been performed, false otherwise.
add(double, double) - Method in class com.arcrobotics.ftclib.util.InterpLUT
 
add(T, R) - Method in class com.arcrobotics.ftclib.util.LUT
 
addButton(Runnable) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Adds a button binding to the scheduler, which will be polled to schedule commands.
addCommands(Command...) - Method in class com.arcrobotics.ftclib.command.CommandGroupBase
Adds the given commands to the command group.
addCommands(Command...) - Method in class com.arcrobotics.ftclib.command.ParallelCommandGroup
 
addCommands(Command...) - Method in class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
 
addCommands(Command...) - Method in class com.arcrobotics.ftclib.command.ParallelRaceGroup
 
addCommands(Command...) - Method in class com.arcrobotics.ftclib.command.SequentialCommandGroup
 
addConstraint(TrajectoryConstraint) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Adds a user-defined constraint to the trajectory.
addConstraints(List<? extends TrajectoryConstraint>) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Adds all user-defined constraints from a list to the trajectory.
addRequirements(Subsystem...) - Method in class com.arcrobotics.ftclib.command.CommandBase
Adds the specified requirements to the command.
addSequential(Command, double) - Method in class com.arcrobotics.ftclib.command.old.CommandOpMode
Deprecated.
addSequential takes in a new command and runs it, delaying any code until the command isFinished.
addSequential(Command, double, double) - Method in class com.arcrobotics.ftclib.command.old.CommandOpMode
Deprecated.
Runs addSequential with a user-specified time interval (in ms)
addTarget(SensorDistanceEx.DistanceTarget) - Method in interface com.arcrobotics.ftclib.hardware.SensorDistanceEx
Adds a DistanceTarget.
addTarget(SensorDistanceEx.DistanceTarget) - Method in class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Adds a DistanceTarget.
addTargets(List<SensorDistanceEx.DistanceTarget>) - Method in interface com.arcrobotics.ftclib.hardware.SensorDistanceEx
Adds an List of DistanceTargets to the targets associated with this device.
addTargets(List<SensorDistanceEx.DistanceTarget>) - Method in class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Adds an List of DistanceTargets to the targets associated with this device.
addTriggeredActions(TriggeredAction...) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Adds the provided TriggeredActions to the path.
addWaypoint(Waypoint) - Method in class com.arcrobotics.ftclib.command.PurePursuitCommand
 
addWaypoints(Waypoint...) - Method in class com.arcrobotics.ftclib.command.PurePursuitCommand
 
alongWith(Command...) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with a set of commands to run parallel to it, ending when the last command ends.
alpha() - Method in class com.arcrobotics.ftclib.hardware.SensorColor
Gets the alpha value from the sensor
and(Trigger) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Composes this trigger with another trigger, returning a new trigger that is active when both triggers are active.
andThen(Command...) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with a set of commands to run after it in sequence.
angle() - Method in class com.arcrobotics.ftclib.geometry.Vector2d
 
angle - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveModuleState
Angle of the module.
angleWrap(double) - Static method in class com.arcrobotics.ftclib.purepursuit.PurePursuitUtil
Wraps the able so it is always in the range [-180, 180].
arcadeDrive(double, double) - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Drives the robot using the arcade system.
arcadeDrive(double, double, boolean) - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Drives the robot using the arcade system.
ArmFeedforward - Class in com.arcrobotics.ftclib.controller.wpilibcontroller
A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting against the force of gravity on a beam suspended at an angle).
ArmFeedforward(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Creates a new ArmFeedforward with the specified gains.
ArmFeedforward(double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Creates a new ArmFeedforward with the specified gains.
asProxy() - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command to run "by proxy" by wrapping it in a ProxyScheduleCommand.
atGoal() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns true if the error is within the tolerance of the error.
atReference() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.RamseteController
Returns true if the pose error is within tolerance of the reference.
atSetPoint() - Method in class com.arcrobotics.ftclib.controller.PIDFController
Returns true if the error is within the percentage of the total input range, determined by PIDFController.setTolerance(double).
atSetpoint() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns true if the error is within the tolerance of the error.
atTarget(double) - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
Determines if the sensor reached the target value (within the threshold error range)
atTargetPosition() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
atTime() - Method in class com.arcrobotics.ftclib.util.Timing.Rate
 

B

beforeStarting(Runnable) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with a runnable to run before this command starts.
blue() - Method in class com.arcrobotics.ftclib.hardware.SensorColor
Gets the blue value from the sensor
Button - Class in com.arcrobotics.ftclib.command.button
This class provides an easy way to link commands to OI inputs.
Button() - Constructor for class com.arcrobotics.ftclib.command.button.Button
Default constructor; creates a button that is never pressed (unless get() is overridden).
Button(BooleanSupplier) - Constructor for class com.arcrobotics.ftclib.command.button.Button
Creates a new button with the given condition determining whether it is pressed.
ButtonReader - Class in com.arcrobotics.ftclib.gamepad
Class that reads the value of button states.
ButtonReader(GamepadEx, GamepadKeys.Button) - Constructor for class com.arcrobotics.ftclib.gamepad.ButtonReader
Initializes controller variables
ButtonReader(BooleanSupplier) - Constructor for class com.arcrobotics.ftclib.gamepad.ButtonReader
 

C

calculate() - Method in class com.arcrobotics.ftclib.controller.PIDFController
Calculates the next output of the PIDF controller.
calculate(double, double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
Calculates the next output of the PIDF controller.
calculate(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
Calculates the control value, u(t).
calculate(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Calculates the feedforward from the gains and setpoints.
calculate(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be zero).
calculate(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Calculates the feedforward from the gains and setpoints.
calculate(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be zero).
calculate(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns the next output of the PID controller.
calculate(double, TrapezoidProfile.State) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns the next output of the PID controller.
calculate(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns the next output of the PIDController.
calculate(double, TrapezoidProfile.State, TrapezoidProfile.Constraints) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns the next output of the PID controller.
calculate(Pose2d, Pose2d, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.RamseteController
Returns the next output of the Ramsete controller.
calculate(Pose2d, Trajectory.State) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.RamseteController
Returns the next output of the Ramsete controller.
calculate(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Calculates the feedforward from the gains and setpoints.
calculate(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be zero).
calculate(double) - Method in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile
Calculate the correct position and velocity for the profile at a time t where the beginning of the profile was at time t = 0.
cancel() - Method in interface com.arcrobotics.ftclib.command.Command
Cancels this command.
cancel(Command...) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Cancels commands.
cancelAll() - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Cancels all commands that are currently scheduled.
cancelWhenActive(Command) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Cancels a command when the trigger becomes active.
cancelWhenPressed(Command) - Method in class com.arcrobotics.ftclib.command.button.Button
Cancels the command when the button is pressed.
centerMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.OdoWheelSpeeds
Speed of strafing
CentripetalAccelerationConstraint - Class in com.arcrobotics.ftclib.trajectory.constraint
A constraint on the maximum absolute centripetal acceleration allowed when traversing a trajectory.
CentripetalAccelerationConstraint(double) - Constructor for class com.arcrobotics.ftclib.trajectory.constraint.CentripetalAccelerationConstraint
Constructs a centripetal acceleration constraint.
ChassisSpeeds - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Represents the speed of a robot chassis.
ChassisSpeeds() - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.ChassisSpeeds
Constructs a ChassisSpeeds with zeros for dx, dy, and theta.
ChassisSpeeds(double, double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.ChassisSpeeds
Constructs a ChassisSpeeds object.
checkAllTargets() - Method in interface com.arcrobotics.ftclib.hardware.SensorDistanceEx
Checks all targets currently associated with this device and returns a Map with the results.
checkAllTargets() - Method in class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Checks all targets currently associated with this device and returns a Map with the results.
clamp(int, int, int) - Static method in class com.arcrobotics.ftclib.util.MathUtils
Returns value clamped between low and high boundaries.
clamp(double, double, double) - Static method in class com.arcrobotics.ftclib.util.MathUtils
Returns value clamped between low and high boundaries.
clearButtons() - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Removes all button bindings from the scheduler.
clearGroupedCommand(Command) - Static method in class com.arcrobotics.ftclib.command.CommandGroupBase
Removes a single command from the list of grouped commands, allowing it to be freely used again.
clearGroupedCommands() - Static method in class com.arcrobotics.ftclib.command.CommandGroupBase
Clears the list of grouped commands, allowing all commands to be freely used again.
clearTotalError() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
clearTriggeredActions() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Removes all TriggeredActions from the path.
clipRange(double) - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
Returns minimum range value if the given value is less than the set minimum.
com.arcrobotics.ftclib.command - package com.arcrobotics.ftclib.command
 
com.arcrobotics.ftclib.command.button - package com.arcrobotics.ftclib.command.button
 
com.arcrobotics.ftclib.command.old - package com.arcrobotics.ftclib.command.old
 
com.arcrobotics.ftclib.controller - package com.arcrobotics.ftclib.controller
 
com.arcrobotics.ftclib.controller.wpilibcontroller - package com.arcrobotics.ftclib.controller.wpilibcontroller
 
com.arcrobotics.ftclib.drivebase - package com.arcrobotics.ftclib.drivebase
 
com.arcrobotics.ftclib.gamepad - package com.arcrobotics.ftclib.gamepad
 
com.arcrobotics.ftclib.geometry - package com.arcrobotics.ftclib.geometry
 
com.arcrobotics.ftclib.hardware - package com.arcrobotics.ftclib.hardware
 
com.arcrobotics.ftclib.hardware.motors - package com.arcrobotics.ftclib.hardware.motors
 
com.arcrobotics.ftclib.kinematics - package com.arcrobotics.ftclib.kinematics
 
com.arcrobotics.ftclib.kinematics.wpilibkinematics - package com.arcrobotics.ftclib.kinematics.wpilibkinematics
 
com.arcrobotics.ftclib.purepursuit - package com.arcrobotics.ftclib.purepursuit
 
com.arcrobotics.ftclib.purepursuit.actions - package com.arcrobotics.ftclib.purepursuit.actions
 
com.arcrobotics.ftclib.purepursuit.types - package com.arcrobotics.ftclib.purepursuit.types
 
com.arcrobotics.ftclib.purepursuit.waypoints - package com.arcrobotics.ftclib.purepursuit.waypoints
 
com.arcrobotics.ftclib.spline - package com.arcrobotics.ftclib.spline
 
com.arcrobotics.ftclib.trajectory - package com.arcrobotics.ftclib.trajectory
 
com.arcrobotics.ftclib.trajectory.constraint - package com.arcrobotics.ftclib.trajectory.constraint
 
com.arcrobotics.ftclib.util - package com.arcrobotics.ftclib.util
 
Command - Interface in com.arcrobotics.ftclib.command
A state machine representing a complete action to be performed by the robot.
Command - Interface in com.arcrobotics.ftclib.command.old
Deprecated.
CommandBase - Class in com.arcrobotics.ftclib.command
A base class for Commands.
CommandBase() - Constructor for class com.arcrobotics.ftclib.command.CommandBase
 
CommandGroupBase - Class in com.arcrobotics.ftclib.command
A base for CommandGroups.
CommandGroupBase() - Constructor for class com.arcrobotics.ftclib.command.CommandGroupBase
 
CommandOpMode - Class in com.arcrobotics.ftclib.command
As opposed to the general WPILib-style Robot paradigm, FTCLib also offers a command opmode for individual opmodes.
CommandOpMode() - Constructor for class com.arcrobotics.ftclib.command.CommandOpMode
 
CommandOpMode - Class in com.arcrobotics.ftclib.command.old
Deprecated.
CommandOpMode() - Constructor for class com.arcrobotics.ftclib.command.old.CommandOpMode
Deprecated.
 
CommandScheduler - Class in com.arcrobotics.ftclib.command
The scheduler responsible for running Commands.
compareTo(SwerveModuleState) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveModuleState
Compares two swerve module states.
ConditionalCommand - Class in com.arcrobotics.ftclib.command
Runs one of two commands, depending on the value of the given condition when this command is initialized.
ConditionalCommand(Command, Command, BooleanSupplier) - Constructor for class com.arcrobotics.ftclib.command.ConditionalCommand
Creates a new ConditionalCommand.
Constraints() - Constructor for class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.Constraints
 
Constraints(double, double) - Constructor for class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.Constraints
Construct constraints for a TrapezoidProfile.
ControlVector(double[], double[]) - Constructor for class com.arcrobotics.ftclib.spline.Spline.ControlVector
Instantiates a control vector.
ControlVectorList(int) - Constructor for class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator.ControlVectorList
 
ControlVectorList() - Constructor for class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator.ControlVectorList
 
ControlVectorList(Collection<? extends Spline.ControlVector>) - Constructor for class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator.ControlVectorList
 
createLUT() - Method in class com.arcrobotics.ftclib.util.InterpLUT
Creates a monotone cubic spline from a given set of control points.
CRServo - Class in com.arcrobotics.ftclib.hardware.motors
A continuous rotation servo that uses a motor object to and a P controller to limit speed and acceleration.
CRServo(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.motors.CRServo
The constructor for the CR Servo.
CRServo(HardwareMap, String, double) - Constructor for class com.arcrobotics.ftclib.hardware.motors.CRServo
The constructor for the CR Servo that includes a custom proportional error coefficient.
crServo - Variable in class com.arcrobotics.ftclib.hardware.motors.CRServo
The CR ServoEx motor object.
CubicHermiteSpline - Class in com.arcrobotics.ftclib.spline
 
CubicHermiteSpline(double[], double[], double[], double[]) - Constructor for class com.arcrobotics.ftclib.spline.CubicHermiteSpline
Constructs a cubic hermite spline with the specified control vectors.
currentTime() - Method in class com.arcrobotics.ftclib.util.Timing.Timer
 
curvatureRadPerMeter - Variable in class com.arcrobotics.ftclib.spline.PoseWithCurvature
 
curvatureRadPerMeter - Variable in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 

D

deadlineWith(Command...) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with a set of commands to run parallel to it, ending when the calling command ends and interrupting all the others.
decelerate(double[], double, double, double, double) - Method in class com.arcrobotics.ftclib.purepursuit.PathMotionProfile
Decelerates the motor speeds.
decelerateMotorSpeeds(double[], double, double, long, double, double) - Method in class com.arcrobotics.ftclib.purepursuit.DecelerationController
Adjusts decelerates the motor speeds.
DecelerationController - Class in com.arcrobotics.ftclib.purepursuit
This class is utility class that is used by Path to decelerate the robot as it approaches a destination.
DecelerationController() - Constructor for class com.arcrobotics.ftclib.purepursuit.DecelerationController
Constructs a DecelerationController object.
DifferentialDrive - Class in com.arcrobotics.ftclib.drivebase
A differential drive is one that has two motors or motor groups on either side of the robot.
DifferentialDrive(Motor...) - Constructor for class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Construct a DifferentialDrive.
DifferentialDrive(boolean, Motor...) - Constructor for class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Construct a DifferentialDrive.
DifferentialDriveKinematics - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velocities for a differential drive.
DifferentialDriveKinematics(double) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveKinematics
Constructs a differential drive kinematics object.
DifferentialDriveKinematicsConstraint - Class in com.arcrobotics.ftclib.trajectory.constraint
A class that enforces constraints on the differential drive kinematics.
DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics, double) - Constructor for class com.arcrobotics.ftclib.trajectory.constraint.DifferentialDriveKinematicsConstraint
Constructs a differential drive dynamics constraint.
DifferentialDriveOdometry - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Class for differential drive odometry.
DifferentialDriveOdometry(Rotation2d, Pose2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveOdometry
Constructs a DifferentialDriveOdometry object.
DifferentialDriveOdometry(Rotation2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveOdometry
Constructs a DifferentialDriveOdometry object with the default pose at the origin.
DifferentialDriveVoltageConstraint - Class in com.arcrobotics.ftclib.trajectory.constraint
A class that enforces constraints on differential drive voltage expenditure based on the motor dynamics and the drive kinematics.
DifferentialDriveVoltageConstraint(SimpleMotorFeedforward, DifferentialDriveKinematics, double) - Constructor for class com.arcrobotics.ftclib.trajectory.constraint.DifferentialDriveVoltageConstraint
Creates a new DifferentialDriveVoltageConstraint.
DifferentialDriveWheelSpeeds - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Represents the wheel speeds for a differential drive drivetrain.
DifferentialDriveWheelSpeeds() - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveWheelSpeeds
Constructs a DifferentialDriveWheelSpeeds with zeros for left and right speeds.
DifferentialDriveWheelSpeeds(double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveWheelSpeeds
Constructs a DifferentialDriveWheelSpeeds.
DifferentialOdometry - Class in com.arcrobotics.ftclib.kinematics
The classfile that performs odometry calculations for a differential drivetrain.
DifferentialOdometry(DoubleSupplier, DoubleSupplier, double) - Constructor for class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
 
DifferentialOdometry(double) - Constructor for class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
The constructor that specifies the track width of the robot but defaults the position to (0, 0, 0).
DifferentialOdometry(Pose2d, double) - Constructor for class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
The constructor that specifies the starting position and the track width.
Direction - Enum in com.arcrobotics.ftclib.util
 
disable() - Static method in class com.arcrobotics.ftclib.command.CommandOpMode
 
disable() - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Disables the command scheduler.
disable() - Method in interface com.arcrobotics.ftclib.command.old.Subsystem
Deprecated.
Deactivates the subsystem, rendering it unusable until the next initialization.
disable() - Static method in class com.arcrobotics.ftclib.command.Robot
 
disable() - Method in interface com.arcrobotics.ftclib.hardware.HardwareDevice
 
disable() - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
 
disable() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Disable the motor.
disable() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
Disables all the motor devices.
disable() - Method in class com.arcrobotics.ftclib.hardware.RevColorSensorV3
 
disable() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
 
disable() - Method in class com.arcrobotics.ftclib.hardware.SensorColor
 
disable() - Method in class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
 
disable() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
disablePreferredAngle() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Disables this waypoint's preferredAngle.
disableRetrace() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Disables retrace.
DistanceTarget(DistanceUnit, double) - Constructor for class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
Target must be within the range of the Rev 2m Sensor, which is 2 meters
DistanceTarget(DistanceUnit, double, double) - Constructor for class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
 
DistanceTarget(DistanceUnit, double, double, String) - Constructor for class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
 
div(double) - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Divides the translation by a scalar and returns the new translation.
div(double) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
 
doAction() - Method in interface com.arcrobotics.ftclib.purepursuit.actions.InterruptAction
Performs the action.
doAction(boolean) - Method in class com.arcrobotics.ftclib.purepursuit.actions.TriggeredAction
Perform the triggered action.
done() - Method in class com.arcrobotics.ftclib.util.Timing.Timer
 
dot(Vector2d) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
Returns dot product of this vector with argument.
driveFieldCentric(double, double, double, double) - Method in class com.arcrobotics.ftclib.drivebase.HDrive
 
driveFieldCentric(double, double, double, double) - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Drives the robot from the perspective of the driver.
driveFieldCentric(double, double, double, double, boolean) - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Drives the robot from the perspective of the driver.
driveRobotCentric(double, double, double) - Method in class com.arcrobotics.ftclib.drivebase.HDrive
 
driveRobotCentric(double, double, double) - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Drives the robot from the perspective of the robot itself rather than that of the driver.
driveRobotCentric(double, double, double, boolean) - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Drives the robot from the perspective of the robot itself rather than that of the driver.
driverOp - Variable in class com.arcrobotics.ftclib.command.CommandOpMode
 
dtheta - Variable in class com.arcrobotics.ftclib.geometry.Twist2d
Angular "dtheta" component (radians).
dx - Variable in class com.arcrobotics.ftclib.geometry.Twist2d
Linear "dx" component.
dy - Variable in class com.arcrobotics.ftclib.geometry.Twist2d
Linear "dy" component.

E

ElevatorFeedforward - Class in com.arcrobotics.ftclib.controller.wpilibcontroller
A helper class that computes feedforward outputs for a simple elevator (modeled as a motor acting against the force of gravity).
ElevatorFeedforward(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Creates a new ElevatorFeedforward with the specified gains.
ElevatorFeedforward(double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Creates a new ElevatorFeedforward with the specified gains.
enable() - Static method in class com.arcrobotics.ftclib.command.CommandOpMode
 
enable() - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Enables the command scheduler.
enable() - Static method in class com.arcrobotics.ftclib.command.Robot
 
enableRetrace() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Enables retrace.
encoder - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
 
Encoder(Supplier<Integer>) - Constructor for class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
The encoder object for the motor.
end(boolean) - Method in interface com.arcrobotics.ftclib.command.Command
The action to take when the command ends.
end(boolean) - Method in class com.arcrobotics.ftclib.command.ConditionalCommand
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.FunctionalCommand
 
end() - Method in interface com.arcrobotics.ftclib.command.old.Command
Deprecated.
The action to take when the command ends.
end() - Method in class com.arcrobotics.ftclib.command.old.SequentialCommandGroup
Deprecated.
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.ParallelCommandGroup
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.ParallelRaceGroup
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.PerpetualCommand
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.ProxyScheduleCommand
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.PurePursuitCommand
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.SequentialCommandGroup
 
end(boolean) - Method in class com.arcrobotics.ftclib.command.WaitCommand
 
EndWaypoint - Class in com.arcrobotics.ftclib.purepursuit.waypoints
An end waypoint is an InterruptWaypoint used to represent the end of a path.
EndWaypoint() - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
Constructs an EndWaypoint.
EndWaypoint(Translation2d, Rotation2d, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
Constructs an EndWaypoint with the provided values.
EndWaypoint(Pose2d, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
Constructs an EndWaypoint with the provided values.
EndWaypoint(double, double, double, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
Constructs an EndWaypoint with the provided values.
equals(Object) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Checks equality between this Pose2d and another object.
equals(Object) - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Checks equality between this Rotation2d and another object.
equals(Object) - Method in class com.arcrobotics.ftclib.geometry.Transform2d
Checks equality between this Transform2d and another object.
equals(Object) - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Checks equality between this Translation2d and another object.
equals(Object) - Method in class com.arcrobotics.ftclib.geometry.Twist2d
Checks equality between this Twist2d and another object.
equals(Object) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
Checks equality between this Vector2d and another object
equals(Object) - Method in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
equals(Object) - Method in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.State
 
execute() - Method in interface com.arcrobotics.ftclib.command.Command
The main body of a command.
execute() - Method in class com.arcrobotics.ftclib.command.ConditionalCommand
 
execute() - Method in class com.arcrobotics.ftclib.command.FunctionalCommand
 
execute() - Method in class com.arcrobotics.ftclib.command.MecanumControllerCommand
 
execute() - Method in interface com.arcrobotics.ftclib.command.old.Command
Deprecated.
The main body of a command.
execute() - Method in class com.arcrobotics.ftclib.command.old.SequentialCommandGroup
Deprecated.
 
execute() - Method in class com.arcrobotics.ftclib.command.ParallelCommandGroup
 
execute() - Method in class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
 
execute() - Method in class com.arcrobotics.ftclib.command.ParallelRaceGroup
 
execute() - Method in class com.arcrobotics.ftclib.command.PerpetualCommand
 
execute() - Method in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
 
execute() - Method in class com.arcrobotics.ftclib.command.ProxyScheduleCommand
 
execute() - Method in class com.arcrobotics.ftclib.command.PurePursuitCommand
Call this in a loop
execute() - Method in class com.arcrobotics.ftclib.command.RamseteCommand
 
execute() - Method in class com.arcrobotics.ftclib.command.SequentialCommandGroup
 
exp(Twist2d) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Obtain a new Pose2d from a (constant curvature) velocity.
ExternalEncoder - Class in com.arcrobotics.ftclib.hardware
This abstract class can be extended to make your own external encoder hardware classes.
ExternalEncoder() - Constructor for class com.arcrobotics.ftclib.hardware.ExternalEncoder
 

F

feedforward - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
 
followPath(MecanumDrive, Odometry) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Initiates the automatic path following feature.
fromDegrees(double) - Static method in class com.arcrobotics.ftclib.geometry.Rotation2d
Constructs and returns a Rotation2d with the given degree value.
fromFieldRelativeSpeeds(double, double, double, Rotation2d) - Static method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.ChassisSpeeds
Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.
frontLeftMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
Speed of the front left wheel.
frontLeftVoltage - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveMotorVoltages
Voltage of the front left motor.
frontRightMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
Speed of the front right wheel.
frontRightVoltage - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveMotorVoltages
Voltage of the front right motor.
FunctionalCommand - Class in com.arcrobotics.ftclib.command
A command that allows the user to pass in functions for each of the basic command methods through the constructor.
FunctionalCommand(Runnable, Runnable, Consumer<Boolean>, BooleanSupplier, Subsystem...) - Constructor for class com.arcrobotics.ftclib.command.FunctionalCommand
Creates a new FunctionalCommand.

G

gamepad - Variable in class com.arcrobotics.ftclib.gamepad.GamepadEx
The retrievable gamepad object
GamepadButton - Class in com.arcrobotics.ftclib.command.button
A Button that gets its state from a GamepadEx.
GamepadButton(GamepadEx, GamepadKeys.Button) - Constructor for class com.arcrobotics.ftclib.command.button.GamepadButton
Creates a gamepad button for triggering commands.
GamepadEx - Class in com.arcrobotics.ftclib.gamepad
An extended gamepad for more advanced toggles, key events, and other control processors.
GamepadEx(Gamepad) - Constructor for class com.arcrobotics.ftclib.gamepad.GamepadEx
The constructor, that contains the gamepad object from the opmode.
GamepadKeys - Class in com.arcrobotics.ftclib.gamepad
An enumerator for the different keys on the gamepad, including bumpers, buttons, and triggers.
GamepadKeys() - Constructor for class com.arcrobotics.ftclib.gamepad.GamepadKeys
 
GamepadKeys.Button - Enum in com.arcrobotics.ftclib.gamepad
 
GamepadKeys.Trigger - Enum in com.arcrobotics.ftclib.gamepad
 
GeneralWaypoint - Class in com.arcrobotics.ftclib.purepursuit.waypoints
A general waypoint is the most common type of Waypoint.
GeneralWaypoint() - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Constructs a GeneralWaypoint.
GeneralWaypoint(double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
 
GeneralWaypoint(Translation2d, Rotation2d, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Constructs a GeneralWaypoint with the provided values.
GeneralWaypoint(Pose2d, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Constructs a GeneralWaypoint with the provided values.
GeneralWaypoint(double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Constructs a GeneralWaypoint with the provided values.
GeneralWaypoint(double, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Constructs a GeneralWaypoint with the provided values.
generateTrajectory(Spline.ControlVector, List<Translation2d>, Spline.ControlVector, TrajectoryConfig) - Static method in class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator
Generates a trajectory from the given control vectors and config.
generateTrajectory(Pose2d, List<Translation2d>, Pose2d, TrajectoryConfig) - Static method in class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator
Generates a trajectory from the given waypoints and config.
generateTrajectory(TrajectoryGenerator.ControlVectorList, TrajectoryConfig) - Static method in class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator
Generates a trajectory from the given quintic control vectors and config.
generateTrajectory(List<Pose2d>, TrajectoryConfig) - Static method in class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator
Generates a trajectory from the given waypoints and config.
get() - Method in class com.arcrobotics.ftclib.command.button.GamepadButton
Gets the value of the joystick button.
get() - Method in class com.arcrobotics.ftclib.command.button.Trigger
Returns whether or not the trigger is active.
get() - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
 
get() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Common method for getting the current set speed of a motor.
get() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
 
get(double) - Method in class com.arcrobotics.ftclib.util.InterpLUT
Interpolates the value of Y = f(X) for given X.
getAbsoluteHeading() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
 
getAbsoluteHeading() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
 
getAchievableMaxTicksPerSecond() - Method in enum com.arcrobotics.ftclib.hardware.motors.Motor.GoBILDA
 
getAngle() - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
 
getAngle() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
getAngleRange() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
getAngles() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
 
getAngles() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
 
getARGB() - Method in class com.arcrobotics.ftclib.hardware.SensorColor
Get all the ARGB values in an array from the sensor
getButton(GamepadKeys.Button) - Method in class com.arcrobotics.ftclib.gamepad.GamepadEx
 
getClosest(T) - Method in class com.arcrobotics.ftclib.util.LUT
Returns the closest possible value for the given key.
getCoefficients() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getCoefficients() - Method in class com.arcrobotics.ftclib.spline.CubicHermiteSpline
Returns the coefficients matrix.
getCoefficients() - Method in class com.arcrobotics.ftclib.spline.QuinticHermiteSpline
Returns the coefficients matrix.
getCoefficients() - Method in class com.arcrobotics.ftclib.spline.Spline
Returns the coefficients of the spline.
getConstraints() - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Returns the user-defined constraints of the trajectory.
getController() - Method in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
Returns the ProfiledPIDController used by the command.
getCorrectedVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
Corrects for velocity overflow
getCorrectedVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getCos() - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Returns the cosine of the rotation.
getCounts() - Method in class com.arcrobotics.ftclib.hardware.ExternalEncoder
 
getCounts() - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
 
getCPR() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getCPR() - Method in enum com.arcrobotics.ftclib.hardware.motors.Motor.GoBILDA
 
getCubicControlVectorsFromWaypoints(Pose2d, Translation2d[], Pose2d) - Static method in class com.arcrobotics.ftclib.spline.SplineHelper
Returns 2 cubic control vectors from a set of exterior waypoints and interior translations.
getCubicSplinesFromControlVectors(Spline.ControlVector, Translation2d[], Spline.ControlVector) - Static method in class com.arcrobotics.ftclib.spline.SplineHelper
Returns a set of cubic splines corresponding to the provided control vectors.
getCurrentCommand() - Method in interface com.arcrobotics.ftclib.command.Subsystem
Returns the command currently running on this subsystem.
getCurrentPosition() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getD() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getD() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Gets the differential coefficient.
getDefaultCommand(Subsystem) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Gets the default command associated with this subsystem.
getDefaultCommand() - Method in interface com.arcrobotics.ftclib.command.Subsystem
Gets the default command for this subsystem.
getDegrees() - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Returns the degree value of the rotation.
getDeviceType() - Method in interface com.arcrobotics.ftclib.hardware.HardwareDevice
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.RevColorSensorV3
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.SensorColor
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
 
getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
getDistance(Translation2d) - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Calculates the distance between two translations in 2d space.
getDistance() - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
 
getDistance(DistanceUnit) - Method in interface com.arcrobotics.ftclib.hardware.SensorDistance
Gets the current distance from the sensor.
getDistance(DistanceUnit) - Method in class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Gets the current distance from the sensor.
getEndVelocity() - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Returns the starting velocity of the trajectory.
getF() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getFeedforwardCoefficients() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getFollowDistance() - Method in interface com.arcrobotics.ftclib.purepursuit.Waypoint
Returns the follow distance for this waypoint.
getFollowDistance() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
 
getFollowDistance() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
 
getFollowRadius() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Returns the follow radius of this waypoint.
getGoal() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Gets the goal for the ProfiledPIDController.
getHeading() - Method in class com.arcrobotics.ftclib.geometry.Pose2d
 
getHeading() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
 
getHeading() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
 
getI() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getI() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Gets the integral coefficient.
getInitialPose() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
Returns the initial pose of the trajectory.
getInstance() - Static method in class com.arcrobotics.ftclib.command.CommandScheduler
Returns the Scheduler instance.
getInverted() - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
 
getInverted() - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
 
getInverted() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Common method for returning if a motor is in the inverted state or not.
getInverted() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
 
getInverted() - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
 
getInverted() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
getLeftX() - Method in class com.arcrobotics.ftclib.gamepad.GamepadEx
 
getLeftY() - Method in class com.arcrobotics.ftclib.gamepad.GamepadEx
 
getMaxAcceleration() - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Returns the maximum acceleration of the trajectory.
getMaxRPM() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getMaxVelocity() - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Returns the maximum velocity of the trajectory.
getMaxVelocityMetersPerSecond(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.CentripetalAccelerationConstraint
Returns the max velocity given the current pose and curvature.
getMaxVelocityMetersPerSecond(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.DifferentialDriveKinematicsConstraint
Returns the max velocity given the current pose and curvature.
getMaxVelocityMetersPerSecond(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.DifferentialDriveVoltageConstraint
 
getMaxVelocityMetersPerSecond(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.MecanumDriveKinematicsConstraint
Returns the max velocity given the current pose and curvature.
getMaxVelocityMetersPerSecond(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.SwerveDriveKinematicsConstraint
Returns the max velocity given the current pose and curvature.
getMaxVelocityMetersPerSecond(Pose2d, double, double) - Method in interface com.arcrobotics.ftclib.trajectory.constraint.TrajectoryConstraint
Returns the max velocity given the current pose and curvature.
getMinMaxAccelerationMetersPerSecondSq(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.CentripetalAccelerationConstraint
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
getMinMaxAccelerationMetersPerSecondSq(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.DifferentialDriveKinematicsConstraint
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
getMinMaxAccelerationMetersPerSecondSq(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.DifferentialDriveVoltageConstraint
 
getMinMaxAccelerationMetersPerSecondSq(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.MecanumDriveKinematicsConstraint
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
getMinMaxAccelerationMetersPerSecondSq(Pose2d, double, double) - Method in class com.arcrobotics.ftclib.trajectory.constraint.SwerveDriveKinematicsConstraint
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
getMinMaxAccelerationMetersPerSecondSq(Pose2d, double, double) - Method in interface com.arcrobotics.ftclib.trajectory.constraint.TrajectoryConstraint
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
getMovementSpeed() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Returns the movement speed of this waypoint.
getMultiplier() - Method in enum com.arcrobotics.ftclib.hardware.motors.Motor.Direction
 
getName() - Method in interface com.arcrobotics.ftclib.command.Command
 
getName() - Method in class com.arcrobotics.ftclib.command.CommandBase
 
getName() - Method in class com.arcrobotics.ftclib.command.SubsystemBase
 
getName() - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
 
getNorm() - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Returns the norm, or distance from the origin to the translation.
getP() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getP() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Gets the proportional coefficient.
getPeriod() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getPeriod() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Gets the period of this controller.
getPoint(double) - Method in class com.arcrobotics.ftclib.spline.Spline
Gets the pose and curvature at some point t on the spline.
getPose() - Method in class com.arcrobotics.ftclib.command.OdometrySubsystem
 
getPose() - Method in class com.arcrobotics.ftclib.kinematics.Odometry
Returns the Pose2d object that represents the current robot position
getPose() - Method in interface com.arcrobotics.ftclib.purepursuit.Waypoint
Returns this Waypoint's position.
getPose() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
 
getPose() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
 
getPoseMeters() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveOdometry
Returns the position of the robot on the field.
getPoseMeters() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveOdometry
Returns the position of the robot on the field.
getPoseMeters() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveOdometry
Returns the position of the robot on the field.
getPosition() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
 
getPosition() - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
 
getPosition() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
getPositionBuffer() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Returns this waypoint's position buffer.
getPositionCoefficient() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getPositionError() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getPositionError() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns the difference between the setpoint and the measurement.
getPreferredAngle() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Returns this waypoint's preferred angle (in radians).
getQuinticControlVectorsFromWaypoints(List<Pose2d>) - Static method in class com.arcrobotics.ftclib.spline.SplineHelper
Returns quintic control vectors from a set of waypoints.
getQuinticSplinesFromControlVectors(Spline.ControlVector[]) - Static method in class com.arcrobotics.ftclib.spline.SplineHelper
Returns a set of quintic splines corresponding to the provided control vectors.
getRadians() - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
 
getRate() - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
 
getRawVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
 
getRequirements() - Method in interface com.arcrobotics.ftclib.command.Command
Specifies the set of subsystems used by this command.
getRequirements() - Method in class com.arcrobotics.ftclib.command.CommandBase
 
getRevIMU() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
Get the underlying sensor
getRevolutions() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
 
getRightX() - Method in class com.arcrobotics.ftclib.gamepad.GamepadEx
 
getRightY() - Method in class com.arcrobotics.ftclib.gamepad.GamepadEx
 
getRotation() - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Returns the rotational component of the transformation.
getRotation() - Method in class com.arcrobotics.ftclib.geometry.Transform2d
Returns the rotational component of the transformation.
getRotation2d() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
 
getRotation2d() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
 
getRotationBuffer() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Returns this waypoint's rotation buffer.
getRPM() - Method in enum com.arcrobotics.ftclib.hardware.motors.Motor.GoBILDA
 
getSensorColor() - Method in class com.arcrobotics.ftclib.hardware.RevColorSensorV3
 
getSensorRevTOFDistance() - Method in class com.arcrobotics.ftclib.hardware.RevColorSensorV3
 
getSetPoint() - Method in class com.arcrobotics.ftclib.controller.PIDFController
Returns the current setpoint of the PIDFController.
getSetpoint() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns the current setpoint of the ProfiledPIDController.
getSin() - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Returns the sine of the rotation.
getStartVelocity() - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Returns the starting velocity of the trajectory.
getState() - Method in class com.arcrobotics.ftclib.gamepad.ToggleButtonReader
 
getStates() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
Return the states of the trajectory.
getSubsystem() - Method in class com.arcrobotics.ftclib.command.CommandBase
 
getSubsystem() - Method in class com.arcrobotics.ftclib.command.SubsystemBase
 
getTan() - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Returns the tangent of the rotation.
getTarget() - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
 
getThreshold() - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
Gets the acceptable error range
getTimeout() - Method in interface com.arcrobotics.ftclib.purepursuit.Waypoint
Returns the timeout period of this waypoint.
getTimeout() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
 
getTimeout() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
 
getTolerance() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getTotalTimeSeconds() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
Returns the overall duration of the trajectory.
getTranslation() - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Returns the translation component of the transformation.
getTranslation() - Method in class com.arcrobotics.ftclib.geometry.Transform2d
Returns the translation component of the transformation.
getTrigger(GamepadKeys.Trigger) - Method in class com.arcrobotics.ftclib.gamepad.GamepadEx
 
getTurnSpeed() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Returns the turn speed of this waypoint.
getType() - Method in interface com.arcrobotics.ftclib.purepursuit.Waypoint
Returns this WayPoint's type.
getType() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
 
getType() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
 
getType() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
 
getType() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
 
getType() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
 
getUnit() - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
Gets the unit of distance
getVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
 
getVelocityError() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
getVelocityError() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Returns the change in error per second.
getVeloCoefficients() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
getX() - Method in class com.arcrobotics.ftclib.geometry.Pose2d
 
getX() - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Returns the X component of the translation.
getX() - Method in class com.arcrobotics.ftclib.geometry.Vector2d
the x component of the vector
getY() - Method in class com.arcrobotics.ftclib.geometry.Pose2d
 
getY() - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Returns the Y component of the translation.
getY() - Method in class com.arcrobotics.ftclib.geometry.Vector2d
the y component of the vector
green() - Method in class com.arcrobotics.ftclib.hardware.SensorColor
Gets the green value from the sensor
GyroEx - Class in com.arcrobotics.ftclib.hardware
 
GyroEx() - Constructor for class com.arcrobotics.ftclib.hardware.GyroEx
 

H

HardwareDevice - Interface in com.arcrobotics.ftclib.hardware
 
hashCode() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
hashCode() - Method in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.State
 
hasRequirement(Subsystem) - Method in interface com.arcrobotics.ftclib.command.Command
Whether the command requires a given subsystem.
hasTraversed() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Returns true if this waypoint has already been traversed, false otherwise.
HDrive - Class in com.arcrobotics.ftclib.drivebase
Holonomic drivebase
HDrive(Motor, Motor, Motor) - Constructor for class com.arcrobotics.ftclib.drivebase.HDrive
Constructor for the H-Drive class, which requires at least three motors.
HDrive(Motor, Motor, Motor, double, double, double) - Constructor for class com.arcrobotics.ftclib.drivebase.HDrive
The constructor that includes the angles of the motors.
HDrive(Motor...) - Constructor for class com.arcrobotics.ftclib.drivebase.HDrive
Sets up the constructor for the holonomic drive.
HolonomicOdometry - Class in com.arcrobotics.ftclib.kinematics
 
HolonomicOdometry(DoubleSupplier, DoubleSupplier, DoubleSupplier, double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
 
HolonomicOdometry(Pose2d, double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
 
HolonomicOdometry(double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
 
HSVtoARGB(int, float[]) - Method in class com.arcrobotics.ftclib.hardware.SensorColor
Convert HSV value to an ARGB one.

I

inherit(Waypoint) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Copies configuration from the given waypoint.
init() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
 
init() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
Initializes gyro with default parameters.
init(BNO055IMU.Parameters) - Method in class com.arcrobotics.ftclib.hardware.RevIMU
Initializes gyro with custom parameters.
init() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Initiates the path.
initialize() - Method in interface com.arcrobotics.ftclib.command.Command
The initial subroutine of a command.
initialize() - Method in class com.arcrobotics.ftclib.command.CommandOpMode
 
initialize() - Method in class com.arcrobotics.ftclib.command.ConditionalCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.FunctionalCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.InstantCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.MecanumControllerCommand
 
initialize() - Method in interface com.arcrobotics.ftclib.command.old.Command
Deprecated.
The initial subroutine of a command.
initialize() - Method in class com.arcrobotics.ftclib.command.old.CommandOpMode
Deprecated.
Initialize all objects, set up subsystems, etc...
initialize() - Method in class com.arcrobotics.ftclib.command.old.SequentialCommandGroup
Deprecated.
 
initialize() - Method in interface com.arcrobotics.ftclib.command.old.Subsystem
Deprecated.
The initilizer method.
initialize() - Method in class com.arcrobotics.ftclib.command.ParallelCommandGroup
 
initialize() - Method in class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
 
initialize() - Method in class com.arcrobotics.ftclib.command.ParallelRaceGroup
 
initialize() - Method in class com.arcrobotics.ftclib.command.PerpetualCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.ProxyScheduleCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.PurePursuitCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.RamseteCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.ScheduleCommand
 
initialize() - Method in class com.arcrobotics.ftclib.command.SequentialCommandGroup
 
initialize() - Method in class com.arcrobotics.ftclib.command.WaitCommand
 
initLoop() - Method in class com.arcrobotics.ftclib.command.old.CommandOpMode
Deprecated.
Init loop.
InstantCommand - Class in com.arcrobotics.ftclib.command
A Command that runs instantly; it will initialize, execute once, and end on the same iteration of the scheduler.
InstantCommand(Runnable, Subsystem...) - Constructor for class com.arcrobotics.ftclib.command.InstantCommand
Creates a new InstantCommand that runs the given Runnable with the given requirements.
InstantCommand() - Constructor for class com.arcrobotics.ftclib.command.InstantCommand
Creates a new InstantCommand with a Runnable that does nothing.
InterpLUT - Class in com.arcrobotics.ftclib.util
Performs spline interpolation given a set of control points.
InterpLUT() - Constructor for class com.arcrobotics.ftclib.util.InterpLUT
 
InterruptAction - Interface in com.arcrobotics.ftclib.purepursuit.actions
This interface represents an action that InterruptWaypoint perform when they reach their interrupt point.
interruptOn(BooleanSupplier) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with an interrupt condition.
InterruptWaypoint - Class in com.arcrobotics.ftclib.purepursuit.waypoints
An InterruptWaypoint is a PointTurnWaypoint.
InterruptWaypoint() - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
Constructs an InterruptWaypoint.
InterruptWaypoint(Translation2d, Rotation2d, double, double, double, double, double, InterruptAction) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
Constructs an InterruptWaypoint with the provided values.
InterruptWaypoint(Pose2d, double, double, double, double, double, InterruptAction) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
Constructs an InterruptWaypoint with the provided values.
InterruptWaypoint(double, double, double, double, double, double, double, double, InterruptAction) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
Constructs an InterruptWaypoint with the provided values.
InterruptWaypoint(double, double, double, double, double, double, double, InterruptAction) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
Constructs an InterruptWaypoint with the provided values.
inverse() - Method in class com.arcrobotics.ftclib.geometry.Transform2d
Invert the transformation.
invertGyro() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
Inverts the ouptut of gyro
isDisabled - Static variable in class com.arcrobotics.ftclib.command.Robot
 
isDown() - Method in class com.arcrobotics.ftclib.gamepad.ButtonReader
Checks if the button is down
isDown() - Method in interface com.arcrobotics.ftclib.gamepad.KeyReader
Checks if the button is down
isDown() - Method in class com.arcrobotics.ftclib.gamepad.TriggerReader
Checks if the button is down
isFinished() - Method in interface com.arcrobotics.ftclib.command.Command
Whether the command has finished.
isFinished() - Method in class com.arcrobotics.ftclib.command.ConditionalCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.FunctionalCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.InstantCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.MecanumControllerCommand
 
isFinished() - Method in interface com.arcrobotics.ftclib.command.old.Command
Deprecated.
Whether the command has finished.
isFinished() - Method in class com.arcrobotics.ftclib.command.old.SequentialCommandGroup
Deprecated.
 
isFinished() - Method in class com.arcrobotics.ftclib.command.ParallelCommandGroup
 
isFinished() - Method in class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
 
isFinished() - Method in class com.arcrobotics.ftclib.command.ParallelRaceGroup
 
isFinished() - Method in class com.arcrobotics.ftclib.command.ProxyScheduleCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.PurePursuitCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.RamseteCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.ScheduleCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.SequentialCommandGroup
 
isFinished() - Method in class com.arcrobotics.ftclib.command.WaitCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.command.WaitUntilCommand
 
isFinished() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Returns true if the path has been completed, false otherwise.
isFinished() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
Returns true if the robot has reached this point and the path is finished, false otherwise.
isFinished(double) - Method in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile
Returns true if the profile has reached the goal.
isInFront(Translation2d, Translation2d, Translation2d, Translation2d) - Static method in class com.arcrobotics.ftclib.purepursuit.PurePursuitUtil
Calculates if a point is further along a line then another point.
isLegalPath() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Returns true if this path is legal, false otherwise.
isReversed() - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Returns whether the trajectory is reversed or not.
isRightSideInverted() - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Checks if the right side motors are inverted.
isRightSideInverted() - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Checks if the right side motors are inverted.
isScheduled() - Method in interface com.arcrobotics.ftclib.command.Command
Whether or not the command is currently scheduled.
isScheduled(Command...) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Whether the given commands are running.
isTimerOn() - Method in class com.arcrobotics.ftclib.util.Timing.Timer
 
isTriggered() - Method in class com.arcrobotics.ftclib.purepursuit.actions.TriggeredAction
Returns true if the trigger condition is met and the action should be performed.

J

JSTEncoder - Class in com.arcrobotics.ftclib.hardware
 
JSTEncoder(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.JSTEncoder
 

K

ka - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
 
ka - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
 
ka - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
 
kcos - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
 
kDefaultLeftMotorAngle - Static variable in class com.arcrobotics.ftclib.drivebase.HDrive
 
kDefaultMaxSpeed - Static variable in class com.arcrobotics.ftclib.drivebase.RobotDrive
 
kDefaultRangeMax - Static variable in class com.arcrobotics.ftclib.drivebase.RobotDrive
 
kDefaultRangeMin - Static variable in class com.arcrobotics.ftclib.drivebase.RobotDrive
 
kDefaultRightMotorAngle - Static variable in class com.arcrobotics.ftclib.drivebase.HDrive
 
kDefaultRightSideMultiplier - Static variable in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
 
kDefaultSlideMotorAngle - Static variable in class com.arcrobotics.ftclib.drivebase.HDrive
 
KeyReader - Interface in com.arcrobotics.ftclib.gamepad
 
kg - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
 
ks - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
 
ks - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
 
ks - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
 
kv - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
 
kv - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
 
kv - Variable in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
 

L

lastTimeStamp - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
 
leftMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveWheelSpeeds
Speed of the left side of the robot.
leftMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.OdoWheelSpeeds
Speed of the left side of the robot.
lineCircleIntersection(Translation2d, double, Translation2d, Translation2d) - Static method in class com.arcrobotics.ftclib.purepursuit.PurePursuitUtil
This method finds points where a line intersects with a circle.
log(Pose2d) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Returns a Twist2d that maps this pose to the end pose.
loop() - Method in interface com.arcrobotics.ftclib.command.old.Subsystem
Deprecated.
Loops the subsystem until Subsystem.stop() is called.
loop() - Method in class com.arcrobotics.ftclib.purepursuit.actions.TriggeredAction
Called regularly by the path it is apart of.
loop(double, double, double) - Method in class com.arcrobotics.ftclib.purepursuit.Path
This is the principle path method.
LUT<T extends java.lang.Number,R> - Class in com.arcrobotics.ftclib.util
A lookup table
LUT() - Constructor for class com.arcrobotics.ftclib.util.LUT
 

M

m_command - Variable in class com.arcrobotics.ftclib.command.PerpetualCommand
 
m_controller - Variable in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
 
m_goal - Variable in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
 
m_isFinished - Variable in class com.arcrobotics.ftclib.command.FunctionalCommand
 
m_measurement - Variable in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
 
m_name - Variable in class com.arcrobotics.ftclib.command.CommandBase
 
m_name - Variable in class com.arcrobotics.ftclib.command.SubsystemBase
 
m_odometry - Variable in class com.arcrobotics.ftclib.command.OdometrySubsystem
 
m_onEnd - Variable in class com.arcrobotics.ftclib.command.FunctionalCommand
 
m_onExecute - Variable in class com.arcrobotics.ftclib.command.FunctionalCommand
 
m_onInit - Variable in class com.arcrobotics.ftclib.command.FunctionalCommand
 
m_requirements - Variable in class com.arcrobotics.ftclib.command.CommandBase
 
m_subsystem - Variable in class com.arcrobotics.ftclib.command.CommandBase
 
m_timer - Variable in class com.arcrobotics.ftclib.command.WaitCommand
 
m_useOutput - Variable in class com.arcrobotics.ftclib.command.ProfiledPIDCommand
 
magnitude() - Method in class com.arcrobotics.ftclib.geometry.Vector2d
Returns magnitude (norm) of the vector.
MathUtils - Class in com.arcrobotics.ftclib.util
 
maxAcceleration - Variable in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.Constraints
 
maxAccelerationMetersPerSecondSq - Variable in class com.arcrobotics.ftclib.trajectory.constraint.TrajectoryConstraint.MinMax
 
maxAchievableAcceleration(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Calculates the maximum achievable acceleration given a maximum voltage supply, a position, and a velocity.
maxAchievableAcceleration(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Calculates the maximum achievable acceleration given a maximum voltage supply and a velocity.
maxAchievableAcceleration(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Calculates the maximum achievable acceleration given a maximum voltage supply and a velocity.
maxAchievableVelocity(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Calculates the maximum achievable velocity given a maximum voltage supply, a position, and an acceleration.
maxAchievableVelocity(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Calculates the maximum achievable velocity given a maximum voltage supply and an acceleration.
maxAchievableVelocity(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Calculates the maximum achievable velocity given a maximum voltage supply and an acceleration.
maxOutput - Variable in class com.arcrobotics.ftclib.drivebase.RobotDrive
 
maxVelocity - Variable in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.Constraints
 
MecanumControllerCommand - Class in com.arcrobotics.ftclib.command
A command that uses two PID controllers (PIDController) and a ProfiledPIDController (ProfiledPIDController) to follow a trajectory Trajectory with a mecanum drive.
MecanumControllerCommand(Trajectory, Supplier<Pose2d>, SimpleMotorFeedforward, MecanumDriveKinematics, PIDController, PIDController, ProfiledPIDController, double, PIDController, PIDController, PIDController, PIDController, Supplier<MecanumDriveWheelSpeeds>, Consumer<MecanumDriveMotorVoltages>) - Constructor for class com.arcrobotics.ftclib.command.MecanumControllerCommand
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(Trajectory, Supplier<Pose2d>, MecanumDriveKinematics, PIDController, PIDController, ProfiledPIDController, double, Consumer<MecanumDriveWheelSpeeds>) - Constructor for class com.arcrobotics.ftclib.command.MecanumControllerCommand
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumDrive - Class in com.arcrobotics.ftclib.drivebase
This is a classfile representing the kinematics of a mecanum drivetrain and controls their speed.
MecanumDrive(Motor, Motor, Motor, Motor) - Constructor for class com.arcrobotics.ftclib.drivebase.MecanumDrive
Sets up the constructor for the mecanum drive.
MecanumDrive(boolean, Motor, Motor, Motor, Motor) - Constructor for class com.arcrobotics.ftclib.drivebase.MecanumDrive
Sets up the constructor for the mecanum drive.
MecanumDriveKinematics - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds.
MecanumDriveKinematics(Translation2d, Translation2d, Translation2d, Translation2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveKinematics
Constructs a mecanum drive kinematics object.
MecanumDriveKinematicsConstraint - Class in com.arcrobotics.ftclib.trajectory.constraint
A class that enforces constraints on the mecanum drive kinematics.
MecanumDriveKinematicsConstraint(MecanumDriveKinematics, double) - Constructor for class com.arcrobotics.ftclib.trajectory.constraint.MecanumDriveKinematicsConstraint
Constructs a mecanum drive dynamics constraint.
MecanumDriveMotorVoltages - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Represents the motor voltages for a mecanum drive drivetrain.
MecanumDriveMotorVoltages() - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveMotorVoltages
Constructs a MecanumDriveMotorVoltages with zeros for all member fields.
MecanumDriveMotorVoltages(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveMotorVoltages
Constructs a MecanumDriveMotorVoltages.
MecanumDriveOdometry - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Class for mecanum drive odometry.
MecanumDriveOdometry(MecanumDriveKinematics, Rotation2d, Pose2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveOdometry
Constructs a MecanumDriveOdometry object.
MecanumDriveOdometry(MecanumDriveKinematics, Rotation2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveOdometry
Constructs a MecanumDriveOdometry object with the default pose at the origin.
MecanumDriveWheelSpeeds - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
 
MecanumDriveWheelSpeeds() - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
Constructs a MecanumDriveWheelSpeeds with zeros for all member fields.
MecanumDriveWheelSpeeds(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
Constructs a MecanumDriveWheelSpeeds.
MecanumOdoKinematics - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
 
MecanumOdoKinematics(Translation2d, Translation2d, Translation2d, Translation2d, double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumOdoKinematics
Constructs a mecanum drive kinematics object.
minAccelerationMetersPerSecondSq - Variable in class com.arcrobotics.ftclib.trajectory.constraint.TrajectoryConstraint.MinMax
 
minAchievableAcceleration(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Calculates the minimum achievable acceleration given a maximum voltage supply, a position, and a velocity.
minAchievableAcceleration(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Calculates the minimum achievable acceleration given a maximum voltage supply and a velocity.
minAchievableAcceleration(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Calculates the maximum achievable acceleration given a maximum voltage supply and a velocity.
minAchievableVelocity(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ArmFeedforward
Calculates the minimum achievable velocity given a maximum voltage supply, a position, and an acceleration.
minAchievableVelocity(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ElevatorFeedforward
Calculates the minimum achievable velocity given a maximum voltage supply and an acceleration.
minAchievableVelocity(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Calculates the minimum achievable velocity given a maximum voltage supply and an acceleration.
MinMax(double, double) - Constructor for class com.arcrobotics.ftclib.trajectory.constraint.TrajectoryConstraint.MinMax
Constructs a MinMax.
MinMax() - Constructor for class com.arcrobotics.ftclib.trajectory.constraint.TrajectoryConstraint.MinMax
Constructs a MinMax with default values.
minus(Pose2d) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Returns the Transform2d that maps the one pose to another.
minus(Rotation2d) - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Subtracts the new rotation from the current rotation and returns the new rotation.
minus(Translation2d) - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Subtracts the other translation from the other translation and returns the difference.
minus(Vector2d) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
subtracts two vectors in 2d space and returns a new vector of the difference
Motor - Class in com.arcrobotics.ftclib.hardware.motors
This is the common wrapper for the DcMotor object in the FTC SDK.
Motor() - Constructor for class com.arcrobotics.ftclib.hardware.motors.Motor
 
Motor(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.motors.Motor
Constructs the instance motor for the wrapper
Motor(HardwareMap, String, Motor.GoBILDA) - Constructor for class com.arcrobotics.ftclib.hardware.motors.Motor
Constructs the instance motor for the wrapper
motor - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
 
Motor.Direction - Enum in com.arcrobotics.ftclib.hardware.motors
 
Motor.Encoder - Class in com.arcrobotics.ftclib.hardware.motors
 
Motor.GoBILDA - Enum in com.arcrobotics.ftclib.hardware.motors
 
Motor.RunMode - Enum in com.arcrobotics.ftclib.hardware.motors
The RunMode of the motor.
MotorEx - Class in com.arcrobotics.ftclib.hardware.motors
An extended motor class that utilizes more features than the regular motor.
MotorEx(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorEx
Constructs the instance motor for the wrapper
MotorEx(HardwareMap, String, Motor.GoBILDA) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorEx
Constructs the instance motor for the wrapper
motorEx - Variable in class com.arcrobotics.ftclib.hardware.motors.MotorEx
The motor for the MotorEx class.
MotorGroup - Class in com.arcrobotics.ftclib.hardware.motors
Allows multiple Motor objects to be linked together as a single group.
MotorGroup(Motor...) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorGroup
Create a new MotorGroup with the provided Motors.
moveToPosition(double, double, double, double, double, double, boolean) - Static method in class com.arcrobotics.ftclib.purepursuit.PurePursuitUtil
Takes the robot's current position and rotation and calculates the motor powers for the robot to move to the target position.

N

negate() - Method in class com.arcrobotics.ftclib.command.button.Trigger
Creates a new trigger that is active when this trigger is inactive, i.e.
normalize(double[], double) - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
Normalize the wheel speeds
normalize(double[]) - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
Normalize the wheel speeds
normalize(double) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveWheelSpeeds
Normalizes the wheel speeds using some max attainable speed.
normalize(double) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
Normalizes the wheel speeds using some max attainable speed.
normalize(double) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.OdoWheelSpeeds
Normalizes the wheel speeds using some max attainable speed.
normalizeSpeed(double) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Normalizes the given raw speed to be in the range [0, 1]
normalizeSpeed(double) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Normalizes the given double to in the range [0, 1].
normalizeWheelSpeeds(SwerveModuleState[], double) - Static method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveKinematics
Normalizes the wheel speeds using some max attainable speed.

O

Odometry - Class in com.arcrobotics.ftclib.kinematics
 
Odometry(Pose2d) - Constructor for class com.arcrobotics.ftclib.kinematics.Odometry
 
Odometry(Pose2d, double) - Constructor for class com.arcrobotics.ftclib.kinematics.Odometry
 
OdometrySubsystem - Class in com.arcrobotics.ftclib.command
 
OdometrySubsystem(Odometry) - Constructor for class com.arcrobotics.ftclib.command.OdometrySubsystem
Make sure you are using the supplier version of the constructor
OdoWheelSpeeds - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
 
OdoWheelSpeeds() - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.OdoWheelSpeeds
Constructs a OdoWheelSpeeds with zeros for left and right speeds.
OdoWheelSpeeds(double, double, double) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.OdoWheelSpeeds
Constructs a DifferentialDriveWheelSpeeds.
omegaRadiansPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.ChassisSpeeds
Represents the angular velocity of the robot frame.
onCommandExecute(Consumer<Command>) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Adds an action to perform on the execution of any command by the scheduler.
onCommandFinish(Consumer<Command>) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Adds an action to perform on the finishing of any command by the scheduler.
onCommandInitialize(Consumer<Command>) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Adds an action to perform on the initialization of any command by the scheduler.
onCommandInterrupt(Consumer<Command>) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Adds an action to perform on the interruption of any command by the scheduler.
or(Trigger) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Composes this trigger with another trigger, returning a new trigger that is active when either trigger is active.

P

ParallelCommandGroup - Class in com.arcrobotics.ftclib.command
A CommandGroup that runs a set of commands in parallel, ending when the last command ends.
ParallelCommandGroup(Command...) - Constructor for class com.arcrobotics.ftclib.command.ParallelCommandGroup
Creates a new ParallelCommandGroup.
ParallelDeadlineGroup - Class in com.arcrobotics.ftclib.command
A CommandGroup that runs a set of commands in parallel, ending only when a specific command (the "deadline") ends, interrupting all other commands that are still running at that point.
ParallelDeadlineGroup(Command, Command...) - Constructor for class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
Creates a new ParallelDeadlineGroup.
ParallelRaceGroup - Class in com.arcrobotics.ftclib.command
A CommandGroup that runs a set of commands in parallel, ending when any one of the commands ends and interrupting all the others.
ParallelRaceGroup(Command...) - Constructor for class com.arcrobotics.ftclib.command.ParallelRaceGroup
Creates a new ParallelCommandRace.
parameterize(Spline) - Static method in class com.arcrobotics.ftclib.spline.SplineParameterizer
Parameterizes the spline.
parameterize(Spline, double, double) - Static method in class com.arcrobotics.ftclib.spline.SplineParameterizer
Parameterizes the spline.
Path - Class in com.arcrobotics.ftclib.purepursuit
This class represents a pure pursuit path.
Path() - Constructor for class com.arcrobotics.ftclib.purepursuit.Path
Constructs an empty path and sets all settings to their defaults.
Path(Waypoint...) - Constructor for class com.arcrobotics.ftclib.purepursuit.Path
Constructs a path with the given waypoint.
PathMotionProfile - Class in com.arcrobotics.ftclib.purepursuit
This class is utility class that is used by Path to adjust the robot speed as it approaches or leaves a destination.
PathMotionProfile() - Constructor for class com.arcrobotics.ftclib.purepursuit.PathMotionProfile
Constructs a PathMotionProfile object.
PathType - Enum in com.arcrobotics.ftclib.purepursuit.types
An enum with values for each Path type.
pause() - Method in class com.arcrobotics.ftclib.util.Timing.Timer
 
PController - Class in com.arcrobotics.ftclib.controller
 
PController(double) - Constructor for class com.arcrobotics.ftclib.controller.PController
Default constructor, only takes a p-value.
PController(double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.PController
The extended constructor.
pController - Variable in class com.arcrobotics.ftclib.hardware.motors.CRServo
The P controller.
PDController - Class in com.arcrobotics.ftclib.controller
 
PDController(double, double) - Constructor for class com.arcrobotics.ftclib.controller.PDController
Default constructor with just the coefficients
PDController(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.PDController
The extended constructor.
performAction() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
If the action has not already been performed, performs the action.
periodic() - Method in class com.arcrobotics.ftclib.command.OdometrySubsystem
Updates the pose every cycle
periodic() - Method in interface com.arcrobotics.ftclib.command.Subsystem
This method is called periodically by the CommandScheduler.
PerpetualCommand - Class in com.arcrobotics.ftclib.command
A command that runs another command in perpetuity, ignoring that command's end conditions.
PerpetualCommand(Command) - Constructor for class com.arcrobotics.ftclib.command.PerpetualCommand
Creates a new PerpetualCommand.
perpetually() - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command to run perpetually, ignoring its ordinary end conditions.
PIDController - Class in com.arcrobotics.ftclib.controller
 
PIDController(double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.PIDController
Default constructor with just the coefficients
PIDController(double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.PIDController
The extended constructor.
PIDFController - Class in com.arcrobotics.ftclib.controller
This is a PID controller (https://en.wikipedia.org/wiki/PID_controller) for your robot.
PIDFController(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.PIDFController
The base constructor for the PIDF controller
PIDFController(double, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.PIDFController
This is the full constructor for the PIDF controller.
plus(Transform2d) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Transforms the pose by the given transformation and returns the new transformed pose.
plus(Rotation2d) - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Adds two rotations together, with the result being bounded between -pi and pi.
plus(Translation2d) - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Adds two translations in 2d space and returns the sum.
plus(Vector2d) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
adds two vectors in 2d space and returns a new vector of the sum
PointTurnWaypoint - Class in com.arcrobotics.ftclib.purepursuit.waypoints
A point turn waypoint is a special type of waypoint where instead of "curving" around it, the robot will travel to it, make a complete stop, turn towards the next waypoint, and continue.
PointTurnWaypoint() - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Constructs a PointTurnWaypoint.
PointTurnWaypoint(Translation2d, Rotation2d, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Constructs a PointTurnWaypoint with the provided values.
PointTurnWaypoint(Pose2d, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Constructs a PointTurnWaypoint with the provided values.
PointTurnWaypoint(double, double, double, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Constructs a PointTurnWaypoint with the provided values.
PointTurnWaypoint(double, double, double, double, double, double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Constructs a PointTurnWaypoint with the provided values.
Pose2d - Class in com.arcrobotics.ftclib.geometry
A two-dimensional position that includes a Vector2d and a heading angle.
Pose2d() - Constructor for class com.arcrobotics.ftclib.geometry.Pose2d
Constructs a pose at the origin facing toward the positive X axis.
Pose2d(Translation2d, Rotation2d) - Constructor for class com.arcrobotics.ftclib.geometry.Pose2d
Constructs a pose with the specified translation and rotation.
Pose2d(double, double, Rotation2d) - Constructor for class com.arcrobotics.ftclib.geometry.Pose2d
Convenience constructors that takes in x and y values directly instead of having to construct a Translation2d.
poseMeters - Variable in class com.arcrobotics.ftclib.spline.PoseWithCurvature
 
poseMeters - Variable in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
PoseWithCurvature - Class in com.arcrobotics.ftclib.spline
Represents a pair of a pose and a curvature.
PoseWithCurvature(Pose2d, double) - Constructor for class com.arcrobotics.ftclib.spline.PoseWithCurvature
Constructs a PoseWithCurvature.
PoseWithCurvature() - Constructor for class com.arcrobotics.ftclib.spline.PoseWithCurvature
Constructs a PoseWithCurvature with default values.
position - Variable in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.State
 
positionController - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
 
positionEqualsWithBuffer(Translation2d, Translation2d, double) - Static method in class com.arcrobotics.ftclib.purepursuit.PurePursuitUtil
Calculates whether or not two points are equal within a margin of error.
process(double[], double, double, double) - Method in class com.arcrobotics.ftclib.purepursuit.DecelerationController
Adjusts decelerates the motor speeds.
processAccelerate(double[], double, double, double) - Method in class com.arcrobotics.ftclib.purepursuit.PathMotionProfile
Adjusts the motor speeds to accelerate the robot based on this motion profile.
processDecelerate(double[], double, double, double) - Method in class com.arcrobotics.ftclib.purepursuit.PathMotionProfile
Adjusts the motor speeds to decelerate the robot based on this motion profile.
ProfiledPIDCommand - Class in com.arcrobotics.ftclib.command
A command that controls an output with a ProfiledPIDController.
ProfiledPIDCommand(ProfiledPIDController, DoubleSupplier, Supplier<TrapezoidProfile.State>, BiConsumer<Double, TrapezoidProfile.State>, Subsystem...) - Constructor for class com.arcrobotics.ftclib.command.ProfiledPIDCommand
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController.
ProfiledPIDCommand(ProfiledPIDController, DoubleSupplier, DoubleSupplier, BiConsumer<Double, TrapezoidProfile.State>, Subsystem...) - Constructor for class com.arcrobotics.ftclib.command.ProfiledPIDCommand
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController.
ProfiledPIDCommand(ProfiledPIDController, DoubleSupplier, TrapezoidProfile.State, BiConsumer<Double, TrapezoidProfile.State>, Subsystem...) - Constructor for class com.arcrobotics.ftclib.command.ProfiledPIDCommand
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController.
ProfiledPIDCommand(ProfiledPIDController, DoubleSupplier, double, BiConsumer<Double, TrapezoidProfile.State>, Subsystem...) - Constructor for class com.arcrobotics.ftclib.command.ProfiledPIDCommand
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController.
ProfiledPIDController - Class in com.arcrobotics.ftclib.controller.wpilibcontroller
Implements a PID control loop whose setpoint is constrained by a trapezoid profile.
ProfiledPIDController(double, double, double, TrapezoidProfile.Constraints) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd.
project(Vector2d) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
Projects this vector onto another vector
ProxyScheduleCommand - Class in com.arcrobotics.ftclib.command
Schedules the given commands when this command is initialized, and ends when all the commands are no longer scheduled.
ProxyScheduleCommand(Command...) - Constructor for class com.arcrobotics.ftclib.command.ProxyScheduleCommand
Creates a new ProxyScheduleCommand that schedules the given commands when initialized, and ends when they are all no longer scheduled.
PurePursuitCommand - Class in com.arcrobotics.ftclib.command
 
PurePursuitCommand(MecanumDrive, OdometrySubsystem, Waypoint...) - Constructor for class com.arcrobotics.ftclib.command.PurePursuitCommand
 
PurePursuitUtil - Class in com.arcrobotics.ftclib.purepursuit
This class contains various static methods that are used in the pure pursuit algorithm.

Q

QuinticHermiteSpline - Class in com.arcrobotics.ftclib.spline
 
QuinticHermiteSpline(double[], double[], double[], double[]) - Constructor for class com.arcrobotics.ftclib.spline.QuinticHermiteSpline
Constructs a quintic hermite spline with the specified control vectors.

R

raceWith(Command...) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with a set of commands to run parallel to it, ending when the first command ends.
RamseteCommand - Class in com.arcrobotics.ftclib.command
A command that uses a RAMSETE controller (RamseteController) to follow a trajectory Trajectory with a differential drive.
RamseteCommand(Trajectory, Supplier<Pose2d>, RamseteController, SimpleMotorFeedforward, DifferentialDriveKinematics, Supplier<DifferentialDriveWheelSpeeds>, PIDController, PIDController, BiConsumer<Double, Double>) - Constructor for class com.arcrobotics.ftclib.command.RamseteCommand
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
RamseteCommand(Trajectory, Supplier<Pose2d>, RamseteController, DifferentialDriveKinematics, BiConsumer<Double, Double>) - Constructor for class com.arcrobotics.ftclib.command.RamseteCommand
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
RamseteController - Class in com.arcrobotics.ftclib.controller.wpilibcontroller
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to a desired pose along a two-dimensional trajectory.
RamseteController(double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.RamseteController
Construct a Ramsete unicycle controller.
rangeMax - Variable in class com.arcrobotics.ftclib.drivebase.RobotDrive
 
rangeMin - Variable in class com.arcrobotics.ftclib.drivebase.RobotDrive
 
Rate(long) - Constructor for class com.arcrobotics.ftclib.util.Timing.Rate
 
readValue() - Method in class com.arcrobotics.ftclib.gamepad.ButtonReader
Reads button value
readValue() - Method in interface com.arcrobotics.ftclib.gamepad.KeyReader
Reads button value
readValue() - Method in class com.arcrobotics.ftclib.gamepad.TriggerReader
Reads button value
rearLeftMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
Speed of the rear left wheel.
rearLeftVoltage - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveMotorVoltages
Voltage of the rear left motor.
rearRightMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
Speed of the rear right wheel.
rearRightVoltage - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveMotorVoltages
Voltage of the rear right motor.
red() - Method in class com.arcrobotics.ftclib.hardware.SensorColor
Gets the red value from the sensor
register(Subsystem...) - Method in class com.arcrobotics.ftclib.command.CommandOpMode
Registers Subsystem objects to the scheduler
register(Subsystem...) - Method in class com.arcrobotics.ftclib.command.Robot
Registers Subsystem objects to the scheduler
register() - Method in interface com.arcrobotics.ftclib.command.Subsystem
Registers this subsystem with the CommandScheduler, allowing its Subsystem.periodic() method to be called when the scheduler runs.
registerSubsystem(Subsystem...) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Registers subsystems with the scheduler.
relativeTo(Pose2d) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Returns the other pose relative to the current pose.
relativeTo(Pose2d) - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
Transforms all poses in the trajectory so that they are relative to the given pose.
removeTriggeredAction(TriggeredAction) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Removes the first instance of the provided TriggeredAction from the path.
removeWaypointAtIndex(int) - Method in class com.arcrobotics.ftclib.command.PurePursuitCommand
 
requireUngrouped(Command...) - Static method in class com.arcrobotics.ftclib.command.CommandGroupBase
Requires that the specified commands not have been already allocated to a CommandGroup.
requireUngrouped(Collection<Command>) - Static method in class com.arcrobotics.ftclib.command.CommandGroupBase
Requires that the specified commands not have been already allocated to a CommandGroup.
requiring(Subsystem) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Returns the command currently requiring a given subsystem.
reset() - Method in class com.arcrobotics.ftclib.command.CommandOpMode
Cancels all previous commands
reset() - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Resets the CommandScheduler instance
reset() - Method in interface com.arcrobotics.ftclib.command.old.Subsystem
Deprecated.
The reset method.
reset() - Method in class com.arcrobotics.ftclib.command.Robot
Cancels all previous commands
reset() - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
reset() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Reset the previous error, the integral term, and disable the controller.
reset(TrapezoidProfile.State) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Reset the previous error and the integral term.
reset(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Reset the previous error and the integral term.
reset(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Reset the previous error and the integral term.
reset() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
 
reset() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
Resets the encoder without having to stop the motor.
reset() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
 
reset() - Method in class com.arcrobotics.ftclib.purepursuit.actions.TriggeredAction
Resets this actions.
reset() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Resets all the waypoints/timeouts/actions in this path.
reset() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
 
reset() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Resets this waypoint.
reset() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
 
reset() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
 
reset() - Method in class com.arcrobotics.ftclib.util.Timing.Rate
 
resetEncoder() - Method in class com.arcrobotics.ftclib.hardware.ExternalEncoder
Hard resets the encoder.
resetEncoder() - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
 
resetEncoder() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Resets the encoder.
resetPosition(Pose2d, Rotation2d) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveOdometry
Resets the robot's position on the field.
resetPosition(Pose2d, Rotation2d) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveOdometry
Resets the robot's position on the field.
resetPosition(Pose2d, Rotation2d) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveOdometry
Resets the robot's position on the field.
resetTimeouts() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Resets all timeouts.
resume() - Method in class com.arcrobotics.ftclib.util.Timing.Timer
 
RevColorSensorV3 - Class in com.arcrobotics.ftclib.hardware
This class is a class for the Rev Color Sensor V3, a sensor that includes both a RGB color sensor and an IR Proximity sensor.
RevColorSensorV3() - Constructor for class com.arcrobotics.ftclib.hardware.RevColorSensorV3
 
RevIMU - Class in com.arcrobotics.ftclib.hardware
 
RevIMU(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.RevIMU
Create a new object for the built-in gyro/imu in the Rev Expansion Hub
RevIMU(HardwareMap) - Constructor for class com.arcrobotics.ftclib.hardware.RevIMU
Create a new object for the built-in gyro/imu in the Rev Expansion Hub with the default configuration name of "imu"
RGBtoHSV(int, int, int, float[]) - Method in class com.arcrobotics.ftclib.hardware.SensorColor
Converts an RGB value to an HSV value.
rightMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveWheelSpeeds
Speed of the right side of the robot.
rightMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.OdoWheelSpeeds
Speed of the right side of the robot.
Robot - Class in com.arcrobotics.ftclib.command
This is the Robot class.
Robot() - Constructor for class com.arcrobotics.ftclib.command.Robot
 
RobotDrive - Class in com.arcrobotics.ftclib.drivebase
 
RobotDrive() - Constructor for class com.arcrobotics.ftclib.drivebase.RobotDrive
 
RobotDrive.MotorType - Enum in com.arcrobotics.ftclib.drivebase
The location of the motor on the robot.
robotPose - Variable in class com.arcrobotics.ftclib.kinematics.Odometry
The Pose2d of the robot.
rotate(double) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
 
rotate(double) - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
Rotates by a given positional factor.
rotate(double) - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
rotateBy(Rotation2d) - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Adds the new rotation to the current rotation using a rotation matrix.
rotateBy(Rotation2d) - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Applies a rotation to the translation in 2d space.
rotateBy(double) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
Rotate the vector in Cartesian space.
rotateDegrees(double) - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
Rotates the servo a certain number of degrees.
rotateDegrees(double) - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
rotatePose(double) - Method in class com.arcrobotics.ftclib.kinematics.Odometry
Rotates the position of the robot by a given angle
Rotation2d - Class in com.arcrobotics.ftclib.geometry
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
Rotation2d() - Constructor for class com.arcrobotics.ftclib.geometry.Rotation2d
Constructs a Rotation2d with a default angle of 0 degrees.
Rotation2d(double) - Constructor for class com.arcrobotics.ftclib.geometry.Rotation2d
Constructs a Rotation2d with the given radian value.
Rotation2d(double, double) - Constructor for class com.arcrobotics.ftclib.geometry.Rotation2d
Constructs a Rotation2d with the given x and y (cosine and sine) components.
rotationEqualsWithBuffer(double, double, double) - Static method in class com.arcrobotics.ftclib.purepursuit.PurePursuitUtil
Calculates whether or not two angles are equal within a margin of error.
run() - Method in class com.arcrobotics.ftclib.command.CommandOpMode
Runs the CommandScheduler instance
run() - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Runs a single iteration of the scheduler.
run() - Method in class com.arcrobotics.ftclib.command.old.CommandOpMode
Deprecated.
Run Op Mode.
run() - Method in class com.arcrobotics.ftclib.command.Robot
Runs the CommandScheduler instance
runmode - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
The runmode of the motor
runOpMode() - Method in class com.arcrobotics.ftclib.command.CommandOpMode
 
runOpMode() - Method in class com.arcrobotics.ftclib.command.old.CommandOpMode
Deprecated.
 
runsWhenDisabled() - Method in interface com.arcrobotics.ftclib.command.Command
Whether the given command should run when the robot is disabled.
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.ConditionalCommand
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.ParallelCommandGroup
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.ParallelRaceGroup
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.PerpetualCommand
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.ScheduleCommand
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.SequentialCommandGroup
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.WaitCommand
 
runsWhenDisabled() - Method in class com.arcrobotics.ftclib.command.WaitUntilCommand
 

S

sample(double) - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
Sample the trajectory at a point in time.
scalarProject(Vector2d) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
Returns scalar projection of this vector onto another vector.
scale(double) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
Scales the values of the vector by some scalar
schedule(boolean) - Method in interface com.arcrobotics.ftclib.command.Command
Schedules this command.
schedule() - Method in interface com.arcrobotics.ftclib.command.Command
Schedules this command, defaulting to interruptible.
schedule(Command...) - Method in class com.arcrobotics.ftclib.command.CommandOpMode
Schedules Command objects to the scheduler
schedule(boolean, Command...) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Schedules multiple commands for execution.
schedule(Command...) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Schedules multiple commands for execution, with interruptible defaulted to true.
schedule(Command...) - Method in class com.arcrobotics.ftclib.command.Robot
Schedules Command objects to the scheduler
ScheduleCommand - Class in com.arcrobotics.ftclib.command
Schedules the given commands when this command is initialized.
ScheduleCommand(Command...) - Constructor for class com.arcrobotics.ftclib.command.ScheduleCommand
Creates a new ScheduleCommand that schedules the given commands when initialized.
SensorColor - Class in com.arcrobotics.ftclib.hardware
 
SensorColor(ColorSensor) - Constructor for class com.arcrobotics.ftclib.hardware.SensorColor
Constructs a color sensor, defaults to ARGB
SensorColor(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.SensorColor
Constructs a color sensor using the given hardware map and name, defaults to ARGB
SensorDistance - Interface in com.arcrobotics.ftclib.hardware
 
SensorDistanceEx - Interface in com.arcrobotics.ftclib.hardware
 
SensorDistanceEx.DistanceTarget - Class in com.arcrobotics.ftclib.hardware
Represents a target distance
SensorRevTOFDistance - Class in com.arcrobotics.ftclib.hardware
Class for a time-of-flight distance sensor
SensorRevTOFDistance(DistanceSensor) - Constructor for class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Makes a distance sensor from an FTC DistanceSensor device.
SensorRevTOFDistance(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Makes a distance sensor object from a given HardwareMap and name.
SensorRevTOFDistance(DistanceSensor, List<SensorDistanceEx.DistanceTarget>) - Constructor for class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Makes a distance sensor from an FTC DistanceSensor device and a given list of DistanceTargets
SensorRevTOFDistance(HardwareMap, String, List<SensorDistanceEx.DistanceTarget>) - Constructor for class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Makes a distance sensor from a given HardwareMap and name and a given list of DistanceTargets
SequentialCommandGroup - Class in com.arcrobotics.ftclib.command.old
Deprecated.
SequentialCommandGroup() - Constructor for class com.arcrobotics.ftclib.command.old.SequentialCommandGroup
Deprecated.
 
SequentialCommandGroup - Class in com.arcrobotics.ftclib.command
A CommandGroups that runs a list of commands in sequence.
SequentialCommandGroup(Command...) - Constructor for class com.arcrobotics.ftclib.command.SequentialCommandGroup
Creates a new SequentialCommandGroup.
ServoEx - Interface in com.arcrobotics.ftclib.hardware
An extended servo interface.
set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
 
set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Common method for setting the speed of a motor.
set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
 
set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
Set the speed for each motor in the group
setAction(InterruptAction) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
 
setAction(InterruptAction) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
Sets the action of this InterruptWaypoint.
setConstraints(TrapezoidProfile.Constraints) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Set velocity and acceleration constraints for goal.
setD(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
setD(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the differential coefficient of the PID controller gain.
setDeadline(Command) - Method in class com.arcrobotics.ftclib.command.ParallelDeadlineGroup
Sets the deadline to the given command.
setDefaultCommand(Subsystem, Command) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Sets the default command for a subsystem.
setDefaultCommand(Command) - Method in interface com.arcrobotics.ftclib.command.Subsystem
Sets the default Command of the subsystem.
setDefaultMotionProfile(PathMotionProfile) - Static method in class com.arcrobotics.ftclib.purepursuit.Path
Sets the default motion profile.
setDirection(Motor.Direction) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
Sets the direction of the encoder to forward or reverse
setDistancePerPulse(double) - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
How much distance is covered in one tick of an encoder.
setEndVelocity(double) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Sets the end velocity of the trajectory.
setErrorHandler(BiConsumer<String, StackTraceElement[]>) - Static method in class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator
Set error reporting function.
setF(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
setFeedforwardCoefficients(double, double) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Set the feedforward coefficients for the motor.
setFollowRadius(double) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Sets the follow radius of this waypoint.
setGoal(TrapezoidProfile.State) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the goal for the ProfiledPIDController.
setGoal(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the goal for the ProfiledPIDController.
setI(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
setI(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the integral coefficient of the PID controller gain.
setIntegrationBounds(double, double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
 
setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
 
setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Common method for inverting direction of a motor.
setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
Set the motor group to the inverted direction or forward direction.
setInverted(boolean) - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
Sets the inversion factor of the servo.
setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
setKinematics(DifferentialDriveKinematics) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Adds a differential drive kinematics constraint to ensure that no wheel velocity of a differential drive goes above the max velocity.
setKinematics(MecanumDriveKinematics) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Adds a mecanum drive kinematics constraint to ensure that no wheel velocity of a mecanum drive goes above the max velocity.
setKinematics(SwerveDriveKinematics) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Adds a swerve drive kinematics constraint to ensure that no wheel velocity of a swerve drive goes above the max velocity.
setMaxSpeed(double) - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Sets the max speed of the drivebase, see RobotDrive for more info.
setMaxSpeed(double) - Method in class com.arcrobotics.ftclib.drivebase.HDrive
Sets the max speed of the drivebase, see RobotDrive for more info.
setMaxSpeed(double) - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Sets the max speed of the drivebase, see RobotDrive for more info.
setMaxSpeed(double) - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
Scale the output speed to the specified maxOutput value.
setMotionProfile(PathMotionProfile) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Sets this path's motion profile to the provided PathMotionProfile.
setMovementSpeed(double) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Sets the movement speed of this waypoint.
setName(String) - Method in class com.arcrobotics.ftclib.command.CommandBase
 
setName(String) - Method in class com.arcrobotics.ftclib.command.SubsystemBase
 
setName(String) - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
Changes the name of the sensor
setP(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
setP(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the proportional coefficient of the PID controller gain.
setPathTimeout(long) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Sets a timeout for the entire path.
setPathType(PathType) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Sets the path type to the specified type.
setPID(double, double, double) - Method in class com.arcrobotics.ftclib.controller.PIDController
 
setPID(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the PID Controller gain parameters.
setPIDF(double, double, double, double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
 
setPosition(double) - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
Sets the position of the servo to the specified location.
setPosition(double) - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
setPositionBuffer(double) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Sets this waypoint's position buffer.
setPositionCoefficient(double) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Set the proportional gain for the position controller.
setPositionTolerance(double) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
 
setPreferredAngle(double) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Sets and enables this waypoint's preferred angle.
setRange(double, double) - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Sets the range of the input, see RobotDrive for more info.
setRange(double, double) - Method in class com.arcrobotics.ftclib.drivebase.HDrive
Sets the range of the input, see RobotDrive for more info.
setRange(double, double) - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Sets the range of the input, see RobotDrive for more info.
setRange(double, double) - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
Sets the clipped range for the drive inputs.
setRange(double, double) - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
Sets the range of the servo.
setRange(double, double) - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
setRetraceSettings(double, double) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Configures the retrace settings.
setReversed(boolean) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Sets the reversed flag of the trajectory.
setRightSideInverted(boolean) - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Sets the right side inversion factor to the specified boolean.
setRightSideInverted(boolean) - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Sets the right side inversion factor to the specified boolean.
setRotationBuffer(double) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Sets this waypoint's rotation buffer.
setRunMode(Motor.RunMode) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Sets the Motor.RunMode of the motor
setSetPoint(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
Sets the setpoint for the PIDFController
setStartVelocity(double) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Sets the start velocity of the trajectory.
setSubsystem(String) - Method in class com.arcrobotics.ftclib.command.CommandBase
 
setSubsystem(String) - Method in class com.arcrobotics.ftclib.command.SubsystemBase
 
setTarget(double) - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
Change the target value
setTargetPosition(int) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Sets the target position for the motor to the desired target.
setTimeout(long) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Sets the timeout period of this waypoint.
setTolerance(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
Sets the error which is considered tolerable for use with PIDFController.atSetPoint().
setTolerance(double, double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
Sets the error which is considered tolerable for use with PIDFController.atSetPoint().
setTolerance(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the error which is considered tolerable for use with atSetpoint().
setTolerance(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
Sets the error which is considered tolerable for use with atSetpoint().
setTolerance(Pose2d) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.RamseteController
Sets the pose error which is considered tolerable for use with atReference().
setTraversed() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
Sets this endpoint as traversed.
setTraversed() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
Tells the waypoint that it has been traversed.
setTurnSpeed(double) - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Sets the turn speed of this waypoint.
setUnit(DistanceUnit) - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
Changes the unit of measurement
setVelocity(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
 
setVelocity(double, AngleUnit) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
 
setVeloCoefficients(double, double, double) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Set the velocity pid coefficients for the motor.
setWaypointTimeouts(long...) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Sets the timeouts of n waypoints where n is the amount of arguments provided.
setWaypointTimeouts(long) - Method in class com.arcrobotics.ftclib.purepursuit.Path
Sets the timeout for each individual waypoint to be the value provided.
setZeroPowerBehavior(DcMotor.ZeroPowerBehavior) - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
A wrapper method for the zero power behavior
SimpleMotorFeedforward - Class in com.arcrobotics.ftclib.controller.wpilibcontroller
A helper class that computes feedforward outputs for a simple permanent-magnet DC motor.
SimpleMotorFeedforward(double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Creates a new SimpleMotorFeedforward with the specified gains.
SimpleMotorFeedforward(double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward
Creates a new SimpleMotorFeedforward with the specified gains.
SimpleServo - Class in com.arcrobotics.ftclib.hardware
 
SimpleServo(HardwareMap, String) - Constructor for class com.arcrobotics.ftclib.hardware.SimpleServo
 
SimpleServo(HardwareMap, String, double, double) - Constructor for class com.arcrobotics.ftclib.hardware.SimpleServo
 
speedMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveModuleState
Speed of the wheel of the module.
Spline - Class in com.arcrobotics.ftclib.spline
Represents a two-dimensional parametric spline that interpolates between two points.
Spline.ControlVector - Class in com.arcrobotics.ftclib.spline
Represents a control vector for a spline.
SplineHelper - Class in com.arcrobotics.ftclib.spline
 
SplineParameterizer - Class in com.arcrobotics.ftclib.spline
Class used to parameterize a spline by its arc length.
SplineParameterizer.MalformedSplineException - Exception in com.arcrobotics.ftclib.spline
 
splinePointsFromSplines(Spline[]) - Static method in class com.arcrobotics.ftclib.trajectory.TrajectoryGenerator
Generate spline points from a vector of splines by parameterizing the splines.
squareInput(double) - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
Square magnitude of number while keeping the sign.
start() - Method in class com.arcrobotics.ftclib.util.Timing.Timer
 
StartWaypoint - Class in com.arcrobotics.ftclib.purepursuit.waypoints
A start waypoint represents the first waypoint in a path.
StartWaypoint() - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
Constructs a StartWaypoint.
StartWaypoint(Translation2d) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
Construct a StartWaypoint located at the provided translation.
StartWaypoint(Pose2d) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
Construct a StartWaypoint located at the provided pose.
StartWaypoint(double, double) - Constructor for class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
Construct a StartWaypoint located at the provided coordinate.
State() - Constructor for class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
State(double, double, double, Pose2d, double) - Constructor for class com.arcrobotics.ftclib.trajectory.Trajectory.State
Constructs a State with the specified parameters.
State() - Constructor for class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.State
 
State(double, double) - Constructor for class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.State
 
stateJustChanged() - Method in class com.arcrobotics.ftclib.gamepad.ButtonReader
Checks if the button state has changed
stateJustChanged() - Method in interface com.arcrobotics.ftclib.gamepad.KeyReader
Checks if the button state has changed
stateJustChanged() - Method in class com.arcrobotics.ftclib.gamepad.TriggerReader
Checks if the button state has changed
stop() - Method in interface com.arcrobotics.ftclib.command.old.Subsystem
Deprecated.
Halts the performance of the subsystem, bringing all hardware devices to a stop.
stop() - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Stop the motors.
stop() - Method in class com.arcrobotics.ftclib.drivebase.HDrive
 
stop() - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
Stop the motors.
stop() - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
 
stop() - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
 
stopMotor() - Method in class com.arcrobotics.ftclib.hardware.motors.Motor
Stops motor movement.
stopMotor() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
Stops all motors in the group.
Subsystem - Interface in com.arcrobotics.ftclib.command.old
Deprecated.
Subsystem - Interface in com.arcrobotics.ftclib.command
A robot subsystem.
SubsystemBase - Class in com.arcrobotics.ftclib.command
A base for subsystems and provides a more intuitive method for setting the default command.
SubsystemBase() - Constructor for class com.arcrobotics.ftclib.command.SubsystemBase
 
SwerveDriveKinematics - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states (speed and angle).
SwerveDriveKinematics(Translation2d...) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveKinematics
Constructs a swerve drive kinematics object.
SwerveDriveKinematicsConstraint - Class in com.arcrobotics.ftclib.trajectory.constraint
A class that enforces constraints on the swerve drive kinematics.
SwerveDriveKinematicsConstraint(SwerveDriveKinematics, double) - Constructor for class com.arcrobotics.ftclib.trajectory.constraint.SwerveDriveKinematicsConstraint
Constructs a swerve drive dynamics constraint.
SwerveDriveOdometry - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Class for swerve drive odometry.
SwerveDriveOdometry(SwerveDriveKinematics, Rotation2d, Pose2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveOdometry
Constructs a SwerveDriveOdometry object.
SwerveDriveOdometry(SwerveDriveKinematics, Rotation2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveOdometry
Constructs a SwerveDriveOdometry object with the default pose at the origin.
SwerveModuleState - Class in com.arcrobotics.ftclib.kinematics.wpilibkinematics
Represents the state of one swerve module.
SwerveModuleState() - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveModuleState
Constructs a SwerveModuleState with zeros for speed and angle.
SwerveModuleState(double, Rotation2d) - Constructor for class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveModuleState
Constructs a SwerveModuleState.
syncEncoder() - Method in class com.arcrobotics.ftclib.hardware.ExternalEncoder
Syncs the recorded counts with the current counts reported by the encoder.
syncEncoder() - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
 

T

tankDrive(double, double) - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Drive the robot using the tank system.
tankDrive(double, double, boolean) - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
Drive the robot using the tank system.
targetReached(SensorDistanceEx.DistanceTarget) - Method in interface com.arcrobotics.ftclib.hardware.SensorDistanceEx
Returns whether a given DistanceTarget has been reached
targetReached(SensorDistanceEx.DistanceTarget) - Method in class com.arcrobotics.ftclib.hardware.SensorRevTOFDistance
Returns whether a given DistanceTarget has been reached
timedOut() - Method in class com.arcrobotics.ftclib.purepursuit.Path
Returns true if this path has timed out, false otherwise.
timeLeftUntil(double) - Method in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile
Returns the time left until a target distance in the profile is reached.
timeParameterizeTrajectory(List<PoseWithCurvature>, List<TrajectoryConstraint>, double, double, double, double, boolean) - Static method in class com.arcrobotics.ftclib.trajectory.TrajectoryParameterizer
Parameterize the trajectory by time.
Timer(long, TimeUnit) - Constructor for class com.arcrobotics.ftclib.util.Timing.Timer
Creates a timer with the given length and unit.
Timer(long) - Constructor for class com.arcrobotics.ftclib.util.Timing.Timer
Creates a timer with the given length and a unit of seconds.
times(double) - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Multiplies the current rotation by a scalar.
times(double) - Method in class com.arcrobotics.ftclib.geometry.Transform2d
Scales the transform by the scalar.
times(double) - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Multiplies the translation by a scalar and returns the new translation.
times(double) - Method in class com.arcrobotics.ftclib.geometry.Vector2d
 
timeSeconds - Variable in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
Timing - Class in com.arcrobotics.ftclib.util
Class for a time related items.
Timing() - Constructor for class com.arcrobotics.ftclib.util.Timing
 
Timing.Rate - Class in com.arcrobotics.ftclib.util
Very simple class for a refresh rate timer.
Timing.Timer - Class in com.arcrobotics.ftclib.util
Class for a timer.
toChassisSpeeds(DifferentialDriveWheelSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveKinematics
Returns a chassis speed from left and right component velocities using forward kinematics.
toChassisSpeeds(MecanumDriveWheelSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveKinematics
Performs forward kinematics to return the resulting chassis state from the given wheel speeds.
toChassisSpeeds(OdoWheelSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumOdoKinematics
Performs forward kinematics to return the resulting chassis state from the given wheel speeds.
toChassisSpeeds(SwerveModuleState...) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveKinematics
Performs forward kinematics to return the resulting chassis state from the given module states.
ToggleButtonReader - Class in com.arcrobotics.ftclib.gamepad
Class gets the current state of a toggle button You must call "readValue();" in a loop to get accurate values.
ToggleButtonReader(GamepadEx, GamepadKeys.Button) - Constructor for class com.arcrobotics.ftclib.gamepad.ToggleButtonReader
The constructor that uses the gamepad and button to refer to a certain state toggler.
ToggleButtonReader(BooleanSupplier) - Constructor for class com.arcrobotics.ftclib.gamepad.ToggleButtonReader
The constructor that checks the values returned by a boolean supplier object.
toggleWhenActive(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Toggles a command when the trigger becomes active.
toggleWhenActive(Command) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Toggles a command when the trigger becomes active.
toggleWhenPressed(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Button
Toggles the command whenever the button is pressed (on then off then on).
toggleWhenPressed(Command) - Method in class com.arcrobotics.ftclib.command.button.Button
Toggles the command whenever the button is pressed (on then off then on).
toolOp - Variable in class com.arcrobotics.ftclib.command.CommandOpMode
 
toString() - Method in class com.arcrobotics.ftclib.geometry.Pose2d
 
toString() - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
 
toString() - Method in class com.arcrobotics.ftclib.geometry.Transform2d
 
toString() - Method in class com.arcrobotics.ftclib.geometry.Translation2d
 
toString() - Method in class com.arcrobotics.ftclib.geometry.Twist2d
 
toString() - Method in class com.arcrobotics.ftclib.geometry.Vector2d
 
toString() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.ChassisSpeeds
 
toString() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveWheelSpeeds
 
toString() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveMotorVoltages
 
toString() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveWheelSpeeds
 
toString() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.OdoWheelSpeeds
 
toString() - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveModuleState
 
toString() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.EndWaypoint
 
toString() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
 
toString() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.InterruptWaypoint
 
toString() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.PointTurnWaypoint
 
toString() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.StartWaypoint
 
toString() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
toString() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
 
toString() - Method in class com.arcrobotics.ftclib.util.InterpLUT
 
toSwerveModuleStates(ChassisSpeeds, Translation2d) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveKinematics
Performs inverse kinematics to return the module states from a desired chassis velocity.
toSwerveModuleStates(ChassisSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveKinematics
Performs inverse kinematics.
totalTime() - Method in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile
Returns the total time the profile takes to reach the goal.
toWheelSpeeds(ChassisSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveKinematics
Returns left and right component velocities from a chassis speed using inverse kinematics.
toWheelSpeeds(ChassisSpeeds, Translation2d) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveKinematics
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
toWheelSpeeds(ChassisSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveKinematics
Performs inverse kinematics.
toWheelSpeeds(ChassisSpeeds, Translation2d) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumOdoKinematics
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
toWheelSpeeds(ChassisSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumOdoKinematics
Performs inverse kinematics.
trackWidth - Variable in class com.arcrobotics.ftclib.kinematics.Odometry
The trackwidth of the odometers
trackWidthMeters - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveKinematics
 
Trajectory - Class in com.arcrobotics.ftclib.trajectory
Represents a time-parameterized trajectory.
Trajectory(List<Trajectory.State>) - Constructor for class com.arcrobotics.ftclib.trajectory.Trajectory
Constructs a trajectory from a vector of states.
Trajectory.State - Class in com.arcrobotics.ftclib.trajectory
Represents a time-parameterized trajectory.
TrajectoryConfig - Class in com.arcrobotics.ftclib.trajectory
Represents the configuration for generating a trajectory.
TrajectoryConfig(double, double) - Constructor for class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
Constructs the trajectory configuration class.
TrajectoryConstraint - Interface in com.arcrobotics.ftclib.trajectory.constraint
An interface for defining user-defined velocity and acceleration constraints while generating trajectories.
TrajectoryConstraint.MinMax - Class in com.arcrobotics.ftclib.trajectory.constraint
Represents a minimum and maximum acceleration.
TrajectoryGenerator - Class in com.arcrobotics.ftclib.trajectory
 
TrajectoryGenerator.ControlVectorList - Class in com.arcrobotics.ftclib.trajectory
 
TrajectoryParameterizer - Class in com.arcrobotics.ftclib.trajectory
Class used to parameterize a trajectory by time.
Transform2d - Class in com.arcrobotics.ftclib.geometry
Represents a transformation for a Pose2d.
Transform2d(Pose2d, Pose2d) - Constructor for class com.arcrobotics.ftclib.geometry.Transform2d
Constructs the transform that maps the initial pose to the final pose.
Transform2d(Translation2d, Rotation2d) - Constructor for class com.arcrobotics.ftclib.geometry.Transform2d
Constructs a transform with the given translation and rotation components.
Transform2d() - Constructor for class com.arcrobotics.ftclib.geometry.Transform2d
Constructs the identity transform -- maps an initial pose to itself.
transformBy(Transform2d) - Method in class com.arcrobotics.ftclib.geometry.Pose2d
Transforms the pose by the given transformation and returns the new pose.
transformBy(Transform2d) - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
Transforms all poses in the trajectory by the given transform.
Translation2d - Class in com.arcrobotics.ftclib.geometry
 
Translation2d() - Constructor for class com.arcrobotics.ftclib.geometry.Translation2d
Constructs a Translation2d with X and Y components equal to zero.
Translation2d(double, double) - Constructor for class com.arcrobotics.ftclib.geometry.Translation2d
Constructs a Translation2d with the X and Y components equal to the provided values.
TrapezoidProfile - Class in com.arcrobotics.ftclib.trajectory
A trapezoid-shaped velocity profile.
TrapezoidProfile(TrapezoidProfile.Constraints, TrapezoidProfile.State, TrapezoidProfile.State) - Constructor for class com.arcrobotics.ftclib.trajectory.TrapezoidProfile
Construct a TrapezoidProfile.
TrapezoidProfile(TrapezoidProfile.Constraints, TrapezoidProfile.State) - Constructor for class com.arcrobotics.ftclib.trajectory.TrapezoidProfile
Construct a TrapezoidProfile.
TrapezoidProfile.Constraints - Class in com.arcrobotics.ftclib.trajectory
 
TrapezoidProfile.State - Class in com.arcrobotics.ftclib.trajectory
 
Trigger - Class in com.arcrobotics.ftclib.command.button
This class provides an easy way to link commands to inputs.
Trigger(BooleanSupplier) - Constructor for class com.arcrobotics.ftclib.command.button.Trigger
Creates a new trigger with the given condition determining whether it is active.
Trigger() - Constructor for class com.arcrobotics.ftclib.command.button.Trigger
Creates a new trigger that is always inactive.
TriggeredAction - Class in com.arcrobotics.ftclib.purepursuit.actions
This is an optional feature of paths.
TriggeredAction() - Constructor for class com.arcrobotics.ftclib.purepursuit.actions.TriggeredAction
 
TriggerReader - Class in com.arcrobotics.ftclib.gamepad
 
TriggerReader(GamepadEx, GamepadKeys.Trigger) - Constructor for class com.arcrobotics.ftclib.gamepad.TriggerReader
Initializes controller variables
TriggerReader(GamepadEx, GamepadKeys.Trigger, String, Telemetry) - Constructor for class com.arcrobotics.ftclib.gamepad.TriggerReader
 
turnToAngle(double) - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
Turns the servo position to a set angle.
turnToAngle(double) - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
 
Twist2d - Class in com.arcrobotics.ftclib.geometry
A change in distance along arc since the last pose update.
Twist2d() - Constructor for class com.arcrobotics.ftclib.geometry.Twist2d
 
Twist2d(double, double, double) - Constructor for class com.arcrobotics.ftclib.geometry.Twist2d
Constructs a Twist2d with the given values.
type - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
The motor type

U

unaryMinus() - Method in class com.arcrobotics.ftclib.geometry.Rotation2d
Takes the inverse of the current rotation.
unaryMinus() - Method in class com.arcrobotics.ftclib.geometry.Translation2d
Returns the inverse of the current translation.
unaryMinus() - Method in class com.arcrobotics.ftclib.geometry.Vector2d
returns the inverse of the vector, equivalent to rotating by 180 degrees
unregisterSubsystem(Subsystem...) - Method in class com.arcrobotics.ftclib.command.CommandScheduler
Un-registers subsystems with the scheduler.
update() - Method in class com.arcrobotics.ftclib.command.OdometrySubsystem
Call this at the end of every loop
update(double, double, double) - Method in class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
 
update(Rotation2d, double, double) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.DifferentialDriveOdometry
Updates the robot position on the field using distance measurements from encoders.
updatePose(Pose2d) - Method in class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
Updates the position of the robot.
updatePose() - Method in class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
This does everything for you.
updatePose() - Method in class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
This handles all the calculations for you.
updatePose(Pose2d) - Method in class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
 
updatePose(Pose2d) - Method in class com.arcrobotics.ftclib.kinematics.Odometry
Updates the position of the robot.
updatePose() - Method in class com.arcrobotics.ftclib.kinematics.Odometry
Uses suppliers to update the position of the robot
updatePosition(double, double) - Method in class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
 
updateWithTime(double, Rotation2d, MecanumDriveWheelSpeeds) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.MecanumDriveOdometry
Updates the robot's position on the field using forward kinematics and integration of the pose over time.
updateWithTime(double, Rotation2d, SwerveModuleState...) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveDriveOdometry
Updates the robot's position on the field using forward kinematics and integration of the pose over time.
usingPreferredAngle() - Method in class com.arcrobotics.ftclib.purepursuit.waypoints.GeneralWaypoint
Returns true if this waypoint is using a preferred angle.

V

value - Variable in enum com.arcrobotics.ftclib.drivebase.RobotDrive.MotorType
 
valueOf(String) - Static method in enum com.arcrobotics.ftclib.drivebase.RobotDrive.MotorType
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.gamepad.GamepadKeys.Button
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.gamepad.GamepadKeys.Trigger
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.hardware.motors.Motor.Direction
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.hardware.motors.Motor.GoBILDA
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.hardware.motors.Motor.RunMode
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.purepursuit.types.PathType
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.purepursuit.types.WaypointType
Returns the enum constant of this type with the specified name.
valueOf(String) - Static method in enum com.arcrobotics.ftclib.util.Direction
Returns the enum constant of this type with the specified name.
values() - Static method in enum com.arcrobotics.ftclib.drivebase.RobotDrive.MotorType
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.gamepad.GamepadKeys.Button
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.gamepad.GamepadKeys.Trigger
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.hardware.motors.Motor.Direction
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.hardware.motors.Motor.GoBILDA
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.hardware.motors.Motor.RunMode
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.purepursuit.types.PathType
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.purepursuit.types.WaypointType
Returns an array containing the constants of this enum type, in the order they are declared.
values() - Static method in enum com.arcrobotics.ftclib.util.Direction
Returns an array containing the constants of this enum type, in the order they are declared.
Vector2d - Class in com.arcrobotics.ftclib.geometry
Think of a vector as a ray with a starting point at the origin.
Vector2d() - Constructor for class com.arcrobotics.ftclib.geometry.Vector2d
Default constructor, no params.
Vector2d(double, double) - Constructor for class com.arcrobotics.ftclib.geometry.Vector2d
The constructor that sets up the x and y values for the 2d vector.
Vector2d(Vector2d) - Constructor for class com.arcrobotics.ftclib.geometry.Vector2d
 
velocity - Variable in class com.arcrobotics.ftclib.trajectory.TrapezoidProfile.State
 
velocityMetersPerSecond - Variable in class com.arcrobotics.ftclib.trajectory.Trajectory.State
 
veloController - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor
 
veloEstimate - Variable in class com.arcrobotics.ftclib.hardware.motors.Motor.Encoder
 
vxMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.ChassisSpeeds
Represents forward velocity w.r.t the robot frame of reference.
vyMetersPerSecond - Variable in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.ChassisSpeeds
Represents sideways velocity w.r.t the robot frame of reference.

W

WaitCommand - Class in com.arcrobotics.ftclib.command
A command that does nothing but takes a specified amount of time to finish.
WaitCommand(long) - Constructor for class com.arcrobotics.ftclib.command.WaitCommand
Creates a new WaitCommand.
WaitUntilCommand - Class in com.arcrobotics.ftclib.command
A command that does nothing but ends after a specified condition.
WaitUntilCommand(BooleanSupplier) - Constructor for class com.arcrobotics.ftclib.command.WaitUntilCommand
Creates a new WaitUntilCommand that ends after a given condition becomes true.
wasJustPressed() - Method in class com.arcrobotics.ftclib.gamepad.ButtonReader
Checks if the button was just pressed
wasJustPressed() - Method in interface com.arcrobotics.ftclib.gamepad.KeyReader
Checks if the button was just pressed
wasJustPressed() - Method in class com.arcrobotics.ftclib.gamepad.TriggerReader
Checks if the button was just pressed
wasJustReleased() - Method in class com.arcrobotics.ftclib.gamepad.ButtonReader
Checks if the button was just released
wasJustReleased() - Method in interface com.arcrobotics.ftclib.gamepad.KeyReader
Checks if the button was just released
wasJustReleased() - Method in class com.arcrobotics.ftclib.gamepad.TriggerReader
Checks if the button was just released
Waypoint - Interface in com.arcrobotics.ftclib.purepursuit
A pure pursuit Waypoint is a point in which the robot traverses.
WaypointType - Enum in com.arcrobotics.ftclib.purepursuit.types
An enum with values for each Waypoint type.
whenActive(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Starts the given command whenever the trigger just becomes active.
whenActive(Command) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Starts the given command whenever the trigger just becomes active.
whenActive(Runnable) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Runs the given runnable whenever the trigger just becomes active.
whenFinished(Runnable) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with a runnable to run after the command finishes.
whenHeld(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Button
Starts the given command when the button is first pressed, and cancels it when it is released, but does not start it again if it ends or is otherwise interrupted.
whenHeld(Command) - Method in class com.arcrobotics.ftclib.command.button.Button
Starts the given command when the button is first pressed, and cancels it when it is released, but does not start it again if it ends or is otherwise interrupted.
whenInactive(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Starts the command when the trigger becomes inactive.
whenInactive(Command) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Starts the command when the trigger becomes inactive.
whenInactive(Runnable) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Runs the given runnable when the trigger becomes inactive.
whenPressed(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Button
Starts the given command whenever the button is newly pressed.
whenPressed(Command) - Method in class com.arcrobotics.ftclib.command.button.Button
Starts the given command whenever the button is newly pressed.
whenPressed(Runnable) - Method in class com.arcrobotics.ftclib.command.button.Button
Runs the given runnable whenever the button is newly pressed.
whenReleased(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Button
Starts the command when the button is released.
whenReleased(Command) - Method in class com.arcrobotics.ftclib.command.button.Button
Starts the command when the button is released.
whenReleased(Runnable) - Method in class com.arcrobotics.ftclib.command.button.Button
Runs the given runnable when the button is released.
whileActiveContinuous(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Constantly starts the given command while the button is held.
whileActiveContinuous(Command) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Constantly starts the given command while the button is held.
whileActiveContinuous(Runnable) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Constantly runs the given runnable while the button is held.
whileActiveOnce(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Starts the given command when the trigger initially becomes active, and ends it when it becomes inactive, but does not re-start it in-between.
whileActiveOnce(Command) - Method in class com.arcrobotics.ftclib.command.button.Trigger
Starts the given command when the trigger initially becomes active, and ends it when it becomes inactive, but does not re-start it in-between.
whileHeld(Command, boolean) - Method in class com.arcrobotics.ftclib.command.button.Button
Constantly starts the given command while the button is held.
whileHeld(Command) - Method in class com.arcrobotics.ftclib.command.button.Button
Constantly starts the given command while the button is held.
whileHeld(Runnable) - Method in class com.arcrobotics.ftclib.command.button.Button
Constantly runs the given runnable while the button is held.
withTimeout(long) - Method in interface com.arcrobotics.ftclib.command.Command
Decorates this command with a timeout.

X

x - Variable in class com.arcrobotics.ftclib.spline.Spline.ControlVector
 

Y

y - Variable in class com.arcrobotics.ftclib.spline.Spline.ControlVector
 
A B C D E F G H I J K L M N O P Q R S T U V W X Y 
Skip navigation links