- 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, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Returns the next output of the PID controller.
- calculate(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Returns the next output of the PID controller.
- 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.
- 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.
- clipRange(double) - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
-
Returns minimum range value if the given value is less than
the set minimum.
- CoaxialSwerveDrive - Class in com.arcrobotics.ftclib.drivebase.swerve
-
A swerve drive that uses several
CoaxialSwerveDrive
objects
that act cohesively as a drivebase.
- CoaxialSwerveDrive(double, double, CoaxialSwerveModule...) - Constructor for class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveDrive
-
The constructor for the swerve drivetrain.
- CoaxialSwerveModule - Class in com.arcrobotics.ftclib.drivebase.swerve
-
The module for a swerve drive.
- CoaxialSwerveModule(Motor, Motor, double) - Constructor for class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveModule
-
Constructor for the module.
- com.arcrobotics.ftclib - package com.arcrobotics.ftclib
-
- com.arcrobotics.ftclib.command - package com.arcrobotics.ftclib.command
-
- com.arcrobotics.ftclib.command.commands - package com.arcrobotics.ftclib.command.commands
-
- 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.drivebase.swerve - package com.arcrobotics.ftclib.drivebase.swerve
-
- 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.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
-
- com.arcrobotics.ftclib.util.files - package com.arcrobotics.ftclib.util.files
-
- com.arcrobotics.ftclib.vision - package com.arcrobotics.ftclib.vision
-
- Command - Interface in com.arcrobotics.ftclib.command
-
- CommandOpMode - Class in com.arcrobotics.ftclib.command
-
- CommandOpMode() - Constructor for class com.arcrobotics.ftclib.command.CommandOpMode
-
- compareTo(SwerveModuleState) - Method in class com.arcrobotics.ftclib.kinematics.wpilibkinematics.SwerveModuleState
-
Compares two swerve module states.
- ConstantVeloMecanumOdometry - Class in com.arcrobotics.ftclib.kinematics
-
- ConstantVeloMecanumOdometry(Rotation2d, Pose2d, double) - Constructor for class com.arcrobotics.ftclib.kinematics.ConstantVeloMecanumOdometry
-
- ConstantVeloMecanumOdometry(Rotation2d, double) - Constructor for class com.arcrobotics.ftclib.kinematics.ConstantVeloMecanumOdometry
-
- 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
-
- COUNTS_PER_REV - Variable in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
The counts per revolution of the output shaft, usually listed in the specs for
the motor.
- 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(Motor) - Constructor for class com.arcrobotics.ftclib.hardware.motors.CRServo
-
The constructor for the CR Servo.
- CRServo(Motor, double) - Constructor for class com.arcrobotics.ftclib.hardware.motors.CRServo
-
The constructor for the CR Servo that incldues a custom
proportional error coefficient.
- 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
-
- CustomMotor(HardwareMap, String, double) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- 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() - Constructor for class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
-
Empty constructor.
- 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.
- DiffySwerveDrive - Class in com.arcrobotics.ftclib.drivebase.swerve
-
- DiffySwerveDrive(DiffySwerveModule, DiffySwerveModule) - Constructor for class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveDrive
-
- DiffySwerveDrive(DiffySwerveModule, DiffySwerveModule, boolean) - Constructor for class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveDrive
-
- DiffySwerveModule - Class in com.arcrobotics.ftclib.drivebase.swerve
-
This is a differential swerve module.
- DiffySwerveModule(Motor, Motor) - Constructor for class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
Make sure the motors are already reversed if needed
- DiffySwerveModuleEx - Class in com.arcrobotics.ftclib.drivebase.swerve
-
- DiffySwerveModuleEx(MotorEx, MotorEx) - Constructor for class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Make sure the motors are already reversed if needed
- DiffySwerveModuleEx(MotorEx, MotorEx, double, double, PIDFController) - Constructor for class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Make sure the motors are already reversed if needed
- Direction - Enum in com.arcrobotics.ftclib.util
-
- disable() - Method in interface com.arcrobotics.ftclib.command.Subsystem
-
Deactivates the subsystem, rendering it unusable until the
next initialization.
- disable() - Method in class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveModule
-
Disables the module.
- disable() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveDrive
-
- disable() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
Disables the module.
- 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.EncoderEx
-
Disables the encoder.
- disable() - Method in interface com.arcrobotics.ftclib.hardware.motors.Motor
-
Disable the motor.
- disable() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
-
- disable() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- disable() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
- disable() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- disable() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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
-
- disableContinuousInput() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Disables continuous input.
- disableContinuousInput() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Disables continuous input.
- 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
-
- 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.
- drawRectangle(Mat, int[], Scalar, int) - Method in class com.arcrobotics.ftclib.vision.ExamplePipeLine
-
This will create the rectangles
- drawRectangle(Mat, Rect, Scalar, int) - Method in class com.arcrobotics.ftclib.vision.SkystoneDetector
-
This will create the rectangles
- drive(double, double, double, double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveDrive
-
- drive(Vector2d, Vector2d) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveDrive
-
Angles must be rotated in order to
account for the way the projections work.
- 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.
- driveFieldCentric(double, double, double, double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveDrive
-
Drives the robot using field-centric control scheme.
- driveModule(double, double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveModule
-
Drive the module using two input speeds, one that controls the translational
vector and the other that controls the rotational vector.
- driveModule(double, double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
If both motors in the module spin in the same direction
with the same power, this will result in strict module rotation.
- driveModule(Vector2d) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
- driveModule(Vector2d) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Once the difference between the desired angle
and the current angle reaches 0, the vector becomes
(magnitude, 0), which means it will strictly move forward.
- 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.
- driveRobotCentric(double, double, double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveDrive
-
Drives the robot using robot-centric control scheme.
- 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.
- gamepad - Variable in class com.arcrobotics.ftclib.gamepad.GamepadEx
-
The retrievable gamepad object
- 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
-
- 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.hardware.motors.CRServo
-
- get() - Method in interface com.arcrobotics.ftclib.hardware.motors.Motor
-
Common interface for getting the current set speed of a motor.
- get() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
-
- get() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- get() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- get() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- getAbsoluteHeading() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
-
- getAbsoluteHeading() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
-
- 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
- getBehavior() - Method in enum com.arcrobotics.ftclib.hardware.motors.MotorEx.ZeroPowerBehavior
-
- getButton(GamepadKeys.Button) - Method in class com.arcrobotics.ftclib.gamepad.GamepadEx
-
- 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.
- getContinuousError(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Wraps error around for continuous inputs.
- 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.MotorImpl
-
- getCpr() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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.
- getCurrentPosition() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- getCurrentTicks() - Method in class com.arcrobotics.ftclib.hardware.motors.EncoderEx
-
- getD() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Get the Differential coefficient.
- getD() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Gets the differential coefficient.
- getD() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- 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.EncoderEx
-
- getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
-
- getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
- getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- getDeviceType() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- 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.
- getDistanceTravelled() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
- getEncoderPulses() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- getEndVelocity() - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
-
Returns the starting velocity of the trajectory.
- getF() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- 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.wpilibcontroller.PIDController
-
Get the Integral coefficient.
- getI() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Gets the integral coefficient.
- getI() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- getInitialPose() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
-
Returns the initial pose of the trajectory.
- getInverted() - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
-
- getInverted() - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
-
- getInverted() - Method in interface com.arcrobotics.ftclib.hardware.motors.Motor
-
Common interface 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 class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- getInverted() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
- getInverted() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- getInverted() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- getInverted() - Method in interface com.arcrobotics.ftclib.hardware.ServoEx
-
- getInverted() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
-
- getLastEncoderCounts() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
- 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.
- getMaxVelocity(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
returns the maximum speed of the motor given its rotations per minute.
- getMaxVelocity(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
Returns the maximum velocity of the 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.
- getMode() - Method in enum com.arcrobotics.ftclib.hardware.motors.MotorEx.RunMode
-
- 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.
- getNumRevolutions() - Method in class com.arcrobotics.ftclib.hardware.motors.EncoderEx
-
- getP() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Get the Proportional coefficient.
- getP() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Gets the proportional coefficient.
- getP() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- getPeriod() - Method in class com.arcrobotics.ftclib.controller.PIDFController
-
- getPeriod() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Returns the period of this controller.
- getPeriod() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Gets the period of this controller.
- getPIDFCoefficients() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- 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.kinematics.ConstantVeloMecanumOdometry
-
- 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 interface com.arcrobotics.ftclib.hardware.ServoEx
-
- getPosition() - Method in class com.arcrobotics.ftclib.hardware.SimpleServo
-
- getPositionError() - Method in class com.arcrobotics.ftclib.controller.PIDFController
-
- getPositionError() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Returns the difference between the setpoint and the measurement.
- getPositionError() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Returns the difference between the setpoint and the measurement.
- getPower() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- getPower() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
- getPower() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- 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
-
- getRaw() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- getRawEncoderCounts() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Returns the encoder counts of the motors in the module
- getRawHeading() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Returns the raw heading of the module in degrees
- getRevIMU() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
-
- 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
-
- getRotations() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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.PIDController
-
Returns the current setpoint of the PIDController.
- 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.
- getSkystonePosition() - Method in class com.arcrobotics.ftclib.vision.SkystoneDetector
-
- 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.
- 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
-
- getTargetPosition() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
- getThreshold() - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
-
Gets the acceptable error range
- 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
-
- getUnit() - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
-
Gets the unit of distance
- getVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- getVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
- getVelocity() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- getVelocityError() - Method in class com.arcrobotics.ftclib.controller.PIDFController
-
- getVelocityError() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Returns the velocity error.
- getVelocityError() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Returns the change in error per second.
- 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.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
-
- m_motorOne - Variable in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
- m_motorTwo - Variable in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
- m_safety - Variable in class com.arcrobotics.ftclib.Robot
-
The enabled safety of the robot.
- 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.commands
-
- 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.commands.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.commands.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...) - Constructor for class com.arcrobotics.ftclib.drivebase.MecanumDrive
-
Sets up the constructor for the mecanum drive.
- MecanumDrive(boolean, 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
- moduleHeading - Variable in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
This is the heading of the module.
- Motor - Interface in com.arcrobotics.ftclib.hardware.motors
-
Interface for motor devices.
- MOTOR_1_POWER - Variable in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
- MOTOR_2_POWER - Variable in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
- MotorEx - Class in com.arcrobotics.ftclib.hardware.motors
-
An extended motor class that utilizes more features than the
regular motor.
- MotorEx(Motor, double) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
The constructor for the motor without a PIDF controller.
- MotorEx(Motor, double, PIDFController) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
The constructor for the extended motor that includes a
PIDFController
.
- MotorEx(Motor, double, PIDFController, PController) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
- MotorEx.RunMode - Enum in com.arcrobotics.ftclib.hardware.motors
-
The mode of the motor.
- MotorEx.ZeroPowerBehavior - Enum in com.arcrobotics.ftclib.hardware.motors
-
The behavior of the motor when a speed of 0 is passed.
- 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.
- MotorImpl - Class in com.arcrobotics.ftclib.hardware.motors
-
An implementation of the motor.
- MotorImpl(HardwareMap, String, double) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
References a dcMotor object in the hardware map (located in your
local configuration) and constructs an implemented motor.
- MotorImpl.CustomMotor - Class in com.arcrobotics.ftclib.hardware.motors
-
- MotorImplEx - Class in com.arcrobotics.ftclib.hardware.motors
-
An extended implemented motor.
- MotorImplEx(MotorImpl) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
The constructor or the object.
- MotorImplEx(MotorImpl, PIDFController) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
The constructor for the motor that includes an internal
PIDF controller.
- MotorImplEx(MotorImpl, PIDFController, PController) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
The constructor for the motor that includes an internal
PIDF controller.
- MotorImplEx(HardwareMap, String, double) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- MotorImplEx(HardwareMap, String, double, PIDFController) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- MotorImplEx(HardwareMap, String, double, PIDFController, PController) - Constructor for class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- 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.
- pause() - Method in class com.arcrobotics.ftclib.util.Timing.Timer
-
- pControl(Motor, double, double, double) - Method in class com.arcrobotics.ftclib.controller.PController
-
Implements a p control calculation onto the affected motor.
- pControl(Motor, double, double) - Method in class com.arcrobotics.ftclib.controller.PController
-
Implements a p control calculation onto the affected motor.
- 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, double) - Constructor for class com.arcrobotics.ftclib.controller.PController
-
The extended constructor.
- PIDController - Class in com.arcrobotics.ftclib.controller.wpilibcontroller
-
Implements a PID control loop.
- PIDController(double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Allocates a PIDController with the given constants for Kp, Ki, and Kd and a default period of
0.02 seconds.
- PIDController(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Allocates a PIDController with the given constants for Kp, Ki, and Kd.
- PIDFController - Class in com.arcrobotics.ftclib.controller
-
This is a PID controller (https://en.wikipedia.org/wiki/PID_controller)
for your robot.
- PIDFController(double[]) - Constructor for class com.arcrobotics.ftclib.controller.PIDFController
-
Pre-Condition: coeff is a four-element array: {kP, kI, kD, kF}
- PIDFController(double[], double, double, double) - Constructor for class com.arcrobotics.ftclib.controller.PIDFController
-
This is the full constructor for the PIDF controller.
- pidWrite(double) - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
-
- pidWrite(double) - Method in interface com.arcrobotics.ftclib.hardware.motors.Motor
-
Set power to the given output that has been calculated using pid calculations.
- pidWrite(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
-
- pidWrite(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- pidWrite(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
- pidWrite(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- pidWrite(double) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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
- 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
-
- processFrame(Mat) - Method in class com.arcrobotics.ftclib.vision.ExamplePipeLine
-
- processFrame(Mat) - Method in class com.arcrobotics.ftclib.vision.SkystoneDetector
-
- 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.
- ProfiledPIDController(double, double, double, TrapezoidProfile.Constraints, double) - 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
- RamseteCommand - Class in com.arcrobotics.ftclib.command.commands
-
- RamseteCommand(Trajectory, Supplier<Pose2d>, RamseteController, SimpleMotorFeedforward, DifferentialDriveKinematics, Supplier<DifferentialDriveWheelSpeeds>, PIDController, PIDController, BiConsumer<Double, Double>) - Constructor for class com.arcrobotics.ftclib.command.commands.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.commands.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
- 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.
- reset() - Method in interface com.arcrobotics.ftclib.command.Subsystem
-
The reset method.
- reset() - Method in class com.arcrobotics.ftclib.controller.PIDFController
-
- reset() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Resets the previous error and the integral term.
- reset() - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Reset the previous error, the integral term, and disable the controller.
- reset() - Method in class com.arcrobotics.ftclib.hardware.GyroEx
-
- reset() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- reset() - Method in class com.arcrobotics.ftclib.hardware.RevIMU
-
- reset() - Method in class com.arcrobotics.ftclib.util.Timing.Rate
-
- resetController() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
- 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.MotorEx
-
Resets the encoder value to 0 without stopping the motor, of course.
- resetEncoderCount() - Method in class com.arcrobotics.ftclib.hardware.motors.EncoderEx
-
Resets the encoder count to 0 while running.
- resetEncoders() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Resets the encoder values of the motors
- resetPosition(Pose2d, Rotation2d) - Method in class com.arcrobotics.ftclib.kinematics.ConstantVeloMecanumOdometry
-
- 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.
- 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
-
- RevIMU(HardwareMap) - Constructor for class com.arcrobotics.ftclib.hardware.RevIMU
-
- RGBtoHSV(int, int, int, float[]) - Method in class com.arcrobotics.ftclib.hardware.SensorColor
-
Converts an RGB value to an HSV value.
- right - Variable in class com.arcrobotics.ftclib.vision.ExamplePipeLine
-
- 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
-
This is the Robot class.
- Robot() - Constructor for class com.arcrobotics.ftclib.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.
- robotPos - Variable in class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
-
- robotPose - Variable in class com.arcrobotics.ftclib.kinematics.DifferentialOdometry
-
- 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.DifferentialOdometry
-
Rotates the heading by the specified value.
- rotatePose(double) - Method in class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
-
Rotates the heading by the specified value.
- 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.
- run() - Method in class com.arcrobotics.ftclib.command.CommandOpMode
-
Run Op Mode.
- runMode - Variable in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
- runOpMode() - Method in class com.arcrobotics.ftclib.command.CommandOpMode
-
- runOpMode() - Method in class com.arcrobotics.ftclib.vision.InternalCameraExample
-
- Safety - Enum in com.arcrobotics.ftclib.util
-
SWIFT performs actions quickly.
- 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
- 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
-
Allows you to combine multiple commands into one.
- SequentialCommandGroup() - Constructor for class com.arcrobotics.ftclib.command.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 interface com.arcrobotics.ftclib.hardware.motors.Motor
-
Common interface for setting the speed of a motor.
- set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
Sets the speed of the motor based on the current run mode.
- set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
-
- set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- set(double) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- setCmsPerTick(double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
- setConstraints(TrapezoidProfile.Constraints) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Set velocity and acceleration constraints for goal.
- setCpr(int) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- setD(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Sets the Differential coefficient of the PID controller gain.
- setD(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Sets the differential coefficient of the PID controller gain.
- setDegreesPerTick(double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
- setDistance(double, double) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- setDistancePerPulse(double) - Method in class com.arcrobotics.ftclib.hardware.JSTEncoder
-
How much distance is covered in one tick of an encoder.
- setDistancePerPulse(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
sets the distance per encoder tick
- 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.
- setExternalGearReduction(double) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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.
- setHeadingInterpol(DoubleSupplier) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
You can set this to use the value returned by getRawHeading()
or from an external sensor.
- setI(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Sets the Integral coefficient of the PID controller gain.
- setI(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Sets the integral coefficient of the PID controller gain.
- setIntegratorRange(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Sets the minimum and maximum values for the integrator.
- setIntegratorRange(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Sets the minimum and maximum values for the integrator.
- setInverted(boolean) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
Reverses the module
- 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 interface com.arcrobotics.ftclib.hardware.motors.Motor
-
Common interface for inverting direction of a motor.
- setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
-
- setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
- setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- setInverted(boolean) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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.
- setMode(MotorEx.RunMode) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
Set the run mode of the motor.
- 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.wpilibcontroller.PIDController
-
Sets the Proportional coefficient of the PID controller gain.
- setP(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Sets the proportional coefficient of the PID controller gain.
- setPID(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Sets the PID Controller gain parameters.
- setPID(double, double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.ProfiledPIDController
-
Sets the PID Controller gain parameters.
- 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
-
- setPower(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
Set the power of the motor.
- setPower(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
Sets the power of the motor to a percentage of the maximum speed.
- setPower(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- 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
-
- 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.
- setRightSideInverted(boolean) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveDrive
-
- setRPM(double) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- setRunMode(DcMotor.RunMode) - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- setSafetyMode(Safety) - Method in class com.arcrobotics.ftclib.Robot
-
Sets the safety mode for the robot.
- setSetPoint(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
-
Sets the setpoint for the PIDFController
- setSetpoint(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Sets the setpoint for the PIDController.
- setStartVelocity(double) - Method in class com.arcrobotics.ftclib.trajectory.TrajectoryConfig
-
Sets the start velocity of the trajectory.
- setTarget(double) - Method in class com.arcrobotics.ftclib.hardware.SensorDistanceEx.DistanceTarget
-
Change the target value
- setTargetDistance(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- setTargetPosition(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
Sets the target position of the motor.
- setThreshold(double) - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Allows you to set the threshold value of the PController
- setTolerance(double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
-
- setTolerance(double, double) - Method in class com.arcrobotics.ftclib.controller.PIDFController
-
- setTolerance(double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Sets the error which is considered tolerable for use with atSetpoint().
- setTolerance(double, double) - Method in class com.arcrobotics.ftclib.controller.wpilibcontroller.PIDController
-
Sets the error which is considered tolerable for use with 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().
- 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.MotorImpl.CustomMotor
-
Sets the velocity of the motor in terms of ticks per second.
- setVelocity(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl
-
Sets the velocity of the motor to a set number of ticks per second.
- setVelocity(double) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImplEx
-
- setZeroPowerBehavior(MotorEx.ZeroPowerBehavior) - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
Set the zero power behavior of the motor.
- 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.
- SimpleMotorImpl - Class in com.arcrobotics.ftclib.hardware.motors
-
- SimpleMotorImpl(HardwareMap, Telemetry, String) - Constructor for class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- SimpleMotorImpl(HardwareMap, Telemetry, String, double) - Constructor for class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- 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
-
- SkystoneDetector - Class in com.arcrobotics.ftclib.vision
-
- SkystoneDetector(Telemetry) - Constructor for class com.arcrobotics.ftclib.vision.SkystoneDetector
-
- SkystoneDetector() - Constructor for class com.arcrobotics.ftclib.vision.SkystoneDetector
-
- SkystoneDetector(double, double, double, double, Telemetry) - Constructor for class com.arcrobotics.ftclib.vision.SkystoneDetector
-
- SkystoneDetector(double, double, double, double) - Constructor for class com.arcrobotics.ftclib.vision.SkystoneDetector
-
- SkystoneDetector.SkystonePosition - Enum in com.arcrobotics.ftclib.vision
-
- 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
-
- 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.Subsystem
-
Halts the performance of the subsystem, bringing all
hardware devices to a stop.
- stopAndReset() - Method in class com.arcrobotics.ftclib.hardware.motors.EncoderEx
-
Stops the motor and resets the encoder.
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.DifferentialDrive
-
Stop the motors.
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.HDrive
-
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.MecanumDrive
-
Stop the motors.
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.RobotDrive
-
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveDrive
-
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.swerve.CoaxialSwerveModule
-
Stops the motors.
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveDrive
-
- stopMotor() - Method in class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModule
-
Stops the motion of the module
- stopMotor() - Method in class com.arcrobotics.ftclib.hardware.motors.CRServo
-
- stopMotor() - Method in interface com.arcrobotics.ftclib.hardware.motors.Motor
-
Stops motor movement.
- stopMotor() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorEx
-
Stops the motor, of course.
- stopMotor() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorGroup
-
- stopMotor() - Method in class com.arcrobotics.ftclib.hardware.motors.MotorImpl.CustomMotor
-
- stopMotor() - Method in class com.arcrobotics.ftclib.hardware.motors.SimpleMotorImpl
-
- Subsystem - Interface in com.arcrobotics.ftclib.command
-
The interface for a custom susbsystem.
- 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
-
- 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
- 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.
- 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.trajectory.Trajectory.State
-
- toString() - Method in class com.arcrobotics.ftclib.trajectory.Trajectory
-
- 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.DifferentialOdometry
-
The distance between the left and right main wheels on the robot.
- trackWidth - Variable in class com.arcrobotics.ftclib.kinematics.HolonomicOdometry
-
The distance between the left and right main wheels on the robot.
- 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
-
- 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 class com.arcrobotics.ftclib.drivebase.swerve.DiffySwerveModuleEx
-
Turns the module to a desired angle.
- 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.
- value - Variable in enum com.arcrobotics.ftclib.drivebase.RobotDrive.MotorType
-
- value - Variable in enum com.arcrobotics.ftclib.util.Safety
-
- 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.MotorEx.RunMode
-
Returns the enum constant of this type with the specified name.
- valueOf(String) - Static method in enum com.arcrobotics.ftclib.hardware.motors.MotorEx.ZeroPowerBehavior
-
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.
- valueOf(String) - Static method in enum com.arcrobotics.ftclib.util.Safety
-
Returns the enum constant of this type with the specified name.
- valueOf(String) - Static method in enum com.arcrobotics.ftclib.vision.SkystoneDetector.SkystonePosition
-
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.MotorEx.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.hardware.motors.MotorEx.ZeroPowerBehavior
-
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.
- values() - Static method in enum com.arcrobotics.ftclib.util.Safety
-
Returns an array containing the constants of this enum type, in
the order they are declared.
- values() - Static method in enum com.arcrobotics.ftclib.vision.SkystoneDetector.SkystonePosition
-
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
-
- 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.