Index
All Classes and Interfaces|All Packages|Constant Field Values
A
- AccelerationLimitedDouble - Class in com.mineinjava.quail.util.geometry
- AccelerationLimitedDouble(double) - Constructor for class com.mineinjava.quail.util.geometry.AccelerationLimitedDouble
-
Creates a new AccelerationLimitedValue.
- AccelerationLimitedDouble(double, double, double) - Constructor for class com.mineinjava.quail.util.geometry.AccelerationLimitedDouble
-
Creates a new AccelerationLimitedValue.
- AccelerationLimitedVector - Class in com.mineinjava.quail.util.geometry
-
Represents a vector with input ramping to control acceleration.
- AccelerationLimitedVector(double) - Constructor for class com.mineinjava.quail.util.geometry.AccelerationLimitedVector
-
Creates a new AccelerationLimitedVector.
- AccelerationLimitedVector(Vec2d, Vec2d, double) - Constructor for class com.mineinjava.quail.util.geometry.AccelerationLimitedVector
-
Creates a new AccelerationLimitedVector.
- add(double, double) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Adds the vector to the passed in vector.
- add(RobotMovement) - Method in class com.mineinjava.quail.RobotMovement
- add(Vec2d) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Adds the vector to the passed in vector.
- addDisplacementMarker(Runnable) - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Add a displacement marker to the sequence (runs a runnable when the robot reaches the marker)
- addLocalTemporalMarker(double, Runnable) - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Add a temporal marker to the sequence (runs a runnable after a certain amount of local time)
- addPath(Path) - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Add a path to the sequence
- Angle - Class in com.mineinjava.quail.util.geometry
-
Various utilities for working with angles.
- Angle() - Constructor for class com.mineinjava.quail.util.geometry.Angle
- angleSimilarity(Vec2d) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Cosine squared of half the angle between two vectors
C
- calculateDesiredAngleWrapper(double) - Method in class com.mineinjava.quail.SwerveModuleBase
-
Calulates the angle to set the steering motor to.
- calculateFastOdometry(ArrayList<Vec2d>) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Calculates the robot's movement based on the module positions.
- calculateModuleAngle(double, double) - Method in class com.mineinjava.quail.DifferentialSwerveModuleBase
-
Calculates the module angle based on the positions of the two motors.
- calculateMotorSpeeds(double, double) - Method in class com.mineinjava.quail.DifferentialSwerveModuleBase
-
Calculates the motor speeds for a differential swerve module.
- calculateMoveAngles(Vec2d, double, double) - Method in class com.mineinjava.quail.SwerveDrive
- calculateMoveAngles(Vec2d, double, double, Vec2d) - Method in class com.mineinjava.quail.SwerveDrive
- calculateNewAngleSetpoint(double) - Method in class com.mineinjava.quail.SwerveModuleBase
-
Calculates the angle to set the steering motor to,
- calculateNextDriveMovement() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Calculate the next movement to follow the path.
- calculateOdometry(Vec2d[]) - Method in class com.mineinjava.quail.localization.SwerveOdometry
- calculateOdometry(ArrayList<Vec2d>) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Calculates the robot's velocity based on the module positions.
- calculateOptimizedAngle(double) - Method in class com.mineinjava.quail.SwerveModuleBase
-
"Optimized" motor rotation.
- clamp(double, double, double) - Static method in class com.mineinjava.quail.util.MathUtil
-
clamps a value between a min and a max
- clone() - Method in class com.mineinjava.quail.util.geometry.Vec2d
- com.mineinjava.quail - package com.mineinjava.quail
- com.mineinjava.quail.localization - package com.mineinjava.quail.localization
- com.mineinjava.quail.pathing - package com.mineinjava.quail.pathing
- com.mineinjava.quail.util - package com.mineinjava.quail.util
- com.mineinjava.quail.util.geometry - package com.mineinjava.quail.util.geometry
- Constants - Class in com.mineinjava.quail.util
-
Contains constants used throughout the program.
- Constants() - Constructor for class com.mineinjava.quail.util.Constants
- ConstraintsPair - Class in com.mineinjava.quail.pathing
-
Represents a pair of constraints (max velocity and max acceleration) for use in the path follower.
- ConstraintsPair(double, double) - Constructor for class com.mineinjava.quail.pathing.ConstraintsPair
-
Constructs a new ConstraintsPair with the specified max velocity and max acceleration.
- cross(double, double) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Performs a cross product with the passed vector.
- cross(Vec2d) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Performs a cross product with the passed vector.
- currentAngle - Variable in class com.mineinjava.quail.SwerveModuleBase
- currentSegment - Variable in class com.mineinjava.quail.pathing.PathSequenceFollower
D
- deltaAngle(double, double) - Static method in class com.mineinjava.quail.util.MathUtil
-
Calculates the smallest angle between two angles.
- DifferentialSwerveModuleBase - Class in com.mineinjava.quail
-
A base class for differential swerve modules.
- DifferentialSwerveModuleBase(Vec2d, double, double) - Constructor for class com.mineinjava.quail.DifferentialSwerveModuleBase
- DifferentialSwerveModuleBase(Vec2d, double, double, boolean) - Constructor for class com.mineinjava.quail.DifferentialSwerveModuleBase
- distanceLastToCurrentPoint() - Method in class com.mineinjava.quail.pathing.Path
-
Returns the distance from last point to current point.
- distanceTo(Pose2d) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- distanceTo(Vec2d) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Calculates the smallest angle to the passed vector.
- distanceToCurrentPoint(Pose2d) - Method in class com.mineinjava.quail.pathing.Path
-
Returns the distance from the passed point to the current point.
- distanceToNextPoint(Pose2d) - Method in class com.mineinjava.quail.pathing.Path
-
Returns the distance from the passed point to the next point.
- div(double) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- dot(double, double) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Performs a dot product with the passed vector.
- dot(Vec2d) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Performs a dot product with the passed vector.
- driveRatio - Variable in class com.mineinjava.quail.SwerveModuleBase
E
- EPSILON - Static variable in class com.mineinjava.quail.util.Constants
- epsilonEquals(double, double) - Static method in class com.mineinjava.quail.util.MathUtil
- epsilonEquals(Pose2d) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- epsilonEqualsHeading(Pose2d) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- equals(Object) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- equals(Object) - Method in class com.mineinjava.quail.util.geometry.Vec2d
F
- floormod(double, double) - Static method in class com.mineinjava.quail.util.MathUtil
- followPathSequence() - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Follows the pathsequence using PathFollower and markers
- fromList(double[]) - Method in class com.mineinjava.quail.util.geometry.Pose2d
-
Returns a pose from the given list.
G
- getAngle() - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Calculates the vector's rotation, with 0° being the positive x direction.
- getCurrentPoint() - Method in class com.mineinjava.quail.pathing.Path
-
Returns the current point in the path.
- getCurrentPointIndex() - Method in class com.mineinjava.quail.pathing.Path
-
Gets the index of the current point in the path.
- getCurrentSegment() - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Returns the current segment
- getElapsedTime() - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Returns the elapsed time since the sequence started
- getHeading() - Method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Returns the heading of the robot (usually from a gyroscope or IMU).
- getHeadingVelocity() - Method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Returns the heading velocity of the robot (usually from a gyroscope or IMU).
- getIdealValue() - Method in class com.mineinjava.quail.util.geometry.AccelerationLimitedDouble
-
Gets the ideal Value.
- getIdealVector() - Method in class com.mineinjava.quail.util.geometry.AccelerationLimitedVector
-
Gets the ideal vector.
- getLength() - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Calculates the length of the vector by using the pythagorean theorem.
- getLengthSquared() - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Calculates the squared length of the vector.
- getLocalizer() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Returns the localizer of the robot.
- getLoopTime() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Returns the measured looptime of the path follower (useful for simulation).
- getMaxAcceleration() - Method in class com.mineinjava.quail.pathing.ConstraintsPair
-
Returns the maximum acceleration of the constraints.
- getMaxAcceleration() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Returns the maximum acceleration of the robot.
- getMaxTurnAcceleration() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Returns the maximum turn acceleration of the robot.
- getMaxTurnSpeed() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Returns the maximum turn speed of the robot.
- getMaxVelocity() - Method in class com.mineinjava.quail.pathing.ConstraintsPair
-
Returns the maximum velocity of the constraints.
- getNextPoint() - Method in class com.mineinjava.quail.pathing.Path
-
Gets the next point in the path.
- getOutput() - Method in class com.mineinjava.quail.util.MiniPID
-
Calculate the output value for the current PID cycle.
- getOutput(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Calculate the output value for the current PID cycle.
- getOutput(double, double) - Method in class com.mineinjava.quail.util.MiniPID
-
Calculate the output value for the current PID cycle.
- getPairs(T[]) - Static method in class com.mineinjava.quail.util.MathUtil
-
returns a list of all the pairs that can be formed from a list
- getPath() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Returns the path that the robot is following.
- getPointRelativeToCurrent(int) - Method in class com.mineinjava.quail.pathing.Path
-
Gets the point at the specified index relative to the current point.
- getPose() - Method in class com.mineinjava.quail.localization.KalmanFilterLocalizer
-
Returns the current pose estimate
- getPose() - Method in interface com.mineinjava.quail.localization.Localizer
- getPose() - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Returns the robot's pose when given a change in position as a vector and a change in rotation.
- getPose() - Method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Returns the robot's pose.
- getSegmentCount() - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Return the amount of segments in the sequence
- getSpeed() - Method in class com.mineinjava.quail.pathing.PathFollower
-
Returns the speed of the robot.
- getType() - Method in class com.mineinjava.quail.pathing.SequenceSegment
- getWheelPositions() - Method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Returns the positions of the tracking wheels in the desired distance units (not encoder counts!)
- getWheelVelocities() - Method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Returns the velocities of the tracking wheels in the desired distance units (not encoder counts!)
H
- hashCode() - Method in class com.mineinjava.quail.util.geometry.Pose2d
- hashCode() - Method in class com.mineinjava.quail.util.geometry.Vec2d
- heading - Variable in class com.mineinjava.quail.localization.KalmanFilterLocalizer
- heading - Variable in class com.mineinjava.quail.util.geometry.Pose2d
- headingVec() - Method in class com.mineinjava.quail.util.geometry.Pose2d
-
Converts the heading to a vector.
I
- incrementCurrentPointIndex() - Method in class com.mineinjava.quail.pathing.Path
-
Increments the current point index.
- isFinished() - Method in class com.mineinjava.quail.pathing.Path
- isFinished() - Method in class com.mineinjava.quail.pathing.PathFollower
-
returns true if the robot is finished following the path.
- isFinished() - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Returns true if the sequence is finished
- isHit(double, Pose2d, Pose2d) - Method in class com.mineinjava.quail.util.geometry.Pose2d
-
Detects if the circle with (@code radius) is "hit" by a straight line between (@code robotPose) and (@code oldRobotPose).
- isRunning() - Method in class com.mineinjava.quail.pathing.SequenceSegment
K
- KalmanFilterLocalizer - Class in com.mineinjava.quail.localization
-
Localizer that uses a Kalman Filter.
- KalmanFilterLocalizer(Vec2d, double) - Constructor for class com.mineinjava.quail.localization.KalmanFilterLocalizer
L
- lastPointIndex - Variable in class com.mineinjava.quail.pathing.Path
- lastSpeedVector - Variable in class com.mineinjava.quail.localization.SwerveOdometry
- length() - Method in class com.mineinjava.quail.pathing.Path
-
Returns the overall length of the path assuming the robot paths on straight lines.
- lerp(double, double, double) - Static method in class com.mineinjava.quail.util.MathUtil
-
Basic lerp function.
- lineSegHitCircle(Pose2d, Pose2d, Pose2d, double) - Static method in class com.mineinjava.quail.util.MathUtil
-
Detects if a line segment defined by two positions will intersect a circle with given center and radius.
- Localizer - Interface in com.mineinjava.quail.localization
-
Interface for code that gets the robot's position and/or velocity TODO: make a getVelocity method
M
- MARKER - Enum constant in enum class com.mineinjava.quail.pathing.SegmentType
- MathUtil - Class in com.mineinjava.quail.util
- MathUtil() - Constructor for class com.mineinjava.quail.util.MathUtil
- MiniPID - Class in com.mineinjava.quail.util
-
Small, easy to use PID implementation with advanced controller capability.
- MiniPID(double, double, double) - Constructor for class com.mineinjava.quail.util.MiniPID
-
Create a MiniPID class object.
- MiniPID(double, double, double, double) - Constructor for class com.mineinjava.quail.util.MiniPID
-
Create a MiniPID class object.
- minus(Pose2d) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- moduleVectors - Variable in class com.mineinjava.quail.localization.SwerveOdometry
- motorFlipper - Variable in class com.mineinjava.quail.SwerveModuleBase
- move(RobotMovement, double) - Method in class com.mineinjava.quail.SwerveDrive
-
Attempts to move the drivetrain
N
- nearestPoint(Pose2d, int) - Method in class com.mineinjava.quail.pathing.Path
-
Calculates the nearest point on the path.
- nearestPointIndex(Pose2d, int) - Method in class com.mineinjava.quail.pathing.Path
-
Calculates the index of the nearest point on the path.
- nextMovementVector() - Method in class com.mineinjava.quail.pathing.Path
-
Next movement vector for lookahead.
- nextSegment() - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Moves on to the next segment (can be used to force the sequence to move on)
- norm(double) - Static method in class com.mineinjava.quail.util.geometry.Angle
-
Returns
angle
clamped to[0, 2pi]
. - normalize() - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Normalizes the vector.
- normalizeModuleVectors(Vec2d[]) - Method in class com.mineinjava.quail.SwerveDrive
- normalizeModuleVectors(Vec2d[], double) - Method in class com.mineinjava.quail.SwerveDrive
- normDelta(double) - Static method in class com.mineinjava.quail.util.geometry.Angle
-
Returns
angleDelta
clamped to[-pi, pi]
.
O
- optimized - Variable in class com.mineinjava.quail.SwerveModuleBase
P
- Path - Class in com.mineinjava.quail.pathing
-
Represents a path that the robot can follow.
- Path(ArrayList<Pose2d>) - Constructor for class com.mineinjava.quail.pathing.Path
-
Creates a path with the specified points and final heading.
- PATH - Enum constant in enum class com.mineinjava.quail.pathing.SegmentType
- pathFollower - Variable in class com.mineinjava.quail.pathing.PathSequenceFollower
- PathFollower - Class in com.mineinjava.quail.pathing
-
Class that helps you follow paths
- PathFollower(Localizer, double, double, double, double, MiniPID, double, double, double, double) - Constructor for class com.mineinjava.quail.pathing.PathFollower
- PathFollower(Localizer, Path, double, double, double, double, MiniPID, double, double, double, double) - Constructor for class com.mineinjava.quail.pathing.PathFollower
- PathFollower(Localizer, Path, ConstraintsPair, ConstraintsPair, MiniPID, double, double, double, double) - Constructor for class com.mineinjava.quail.pathing.PathFollower
- PathSequenceFollower - Class in com.mineinjava.quail.pathing
-
DEPRECATED - DO NOT USE A class that helps you follow a sequence of paths
- PathSequenceFollower(PathFollower) - Constructor for class com.mineinjava.quail.pathing.PathSequenceFollower
- plus(Pose2d) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- points - Variable in class com.mineinjava.quail.pathing.Path
- Pose2d - Class in com.mineinjava.quail.util.geometry
-
Represents a two-dimensional position and heading.
- Pose2d() - Constructor for class com.mineinjava.quail.util.geometry.Pose2d
-
Returns zero pose.
- Pose2d(double, double, double) - Constructor for class com.mineinjava.quail.util.geometry.Pose2d
- Pose2d(Vec2d) - Constructor for class com.mineinjava.quail.util.geometry.Pose2d
- Pose2d(Vec2d, double) - Constructor for class com.mineinjava.quail.util.geometry.Pose2d
-
Useful for conversion from vector.
- position - Variable in class com.mineinjava.quail.SwerveModuleBase
R
- relativeOdometryUpdate(Pose2d, Pose2d) - Static method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Returns the robot's releative pose.
- remainingLength(Pose2d) - Method in class com.mineinjava.quail.pathing.Path
-
* Given a position, calculate the distance from that position to the next point then the remaining distance on the path
- reset() - Method in class com.mineinjava.quail.util.MiniPID
-
Resets the controller.
- RobotMovement - Class in com.mineinjava.quail
-
Can represent a lot of things.
- RobotMovement() - Constructor for class com.mineinjava.quail.RobotMovement
- RobotMovement(double) - Constructor for class com.mineinjava.quail.RobotMovement
- RobotMovement(double, double, double) - Constructor for class com.mineinjava.quail.RobotMovement
- RobotMovement(double, Vec2d) - Constructor for class com.mineinjava.quail.RobotMovement
- RobotMovement(Vec2d) - Constructor for class com.mineinjava.quail.RobotMovement
- rotate(double, boolean) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Rotates the vector by the passed amount.
- rotation - Variable in class com.mineinjava.quail.RobotMovement
- run() - Method in class com.mineinjava.quail.pathing.SequenceSegment
S
- scale(double) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Scales the vector.
- segments - Variable in class com.mineinjava.quail.pathing.PathSequenceFollower
- SegmentType - Enum Class in com.mineinjava.quail.pathing
-
DEPRECATED - DO NOT USE
- SequenceSegment - Class in com.mineinjava.quail.pathing
-
DEPRECATED - DO NOT USE
- SequenceSegment(PathSequenceFollower, SegmentType, Runnable) - Constructor for class com.mineinjava.quail.pathing.SequenceSegment
- set(Vec2d) - Method in class com.mineinjava.quail.SwerveModuleBase
-
Sets the module's motion to the specified vector;
- setAngle(double) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Sets the angle of the odometry.
- setAngle(double) - Method in class com.mineinjava.quail.SwerveModuleBase
- setD(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Changes the D parameter.
- setDeadband(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Sets the deadband.
- setDirection(boolean) - Method in class com.mineinjava.quail.util.MiniPID
-
Set the operating direction of the PID controller.
- setF(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Configure the FeedForward parameter.
- setHeading(double) - Method in class com.mineinjava.quail.localization.KalmanFilterLocalizer
-
Sets the current heading.
- setI(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Changes the I parameter.
- setLocalizer(Localizer) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Set the localizer of the robot.
- setMaxAcceleration(double) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the maximum acceleration of the robot.
- setMaxIOutput(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Set the maximum output value contributed by the I component of the system.
- setMaxTurnAcceleration(double) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the maximum turn acceleration of the robot.
- setMaxTurnSpeed(double) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the maximum turn speed of the robot.
- setOutputFilter(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Set a filter on the output to reduce sharp oscillations.
- setOutputLimits(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Specify a maximum output range.
- setOutputLimits(double, double) - Method in class com.mineinjava.quail.util.MiniPID
-
Specify a maximum output.
- setOutputRampRate(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Set the maximum rate the output can increase per cycle.
- setP(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Configure the Proportional gain parameter.
- setPath(Path) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Update the path to follow.
- setPID(double, double, double) - Method in class com.mineinjava.quail.util.MiniPID
-
Configure the PID object.
- setPID(double, double, double, double) - Method in class com.mineinjava.quail.util.MiniPID
-
Configure the PID object.
- setPose(Pose2d) - Method in class com.mineinjava.quail.localization.KalmanFilterLocalizer
-
Sets the current position.
- setPose(Pose2d) - Method in interface com.mineinjava.quail.localization.Localizer
- setPose(Pose2d) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Sets the robot's pose.
- setPose(Pose2d) - Method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Sets the robot's pose.
- setPrecision(double) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the precision of the path follower.
- setRawAngle(double) - Method in class com.mineinjava.quail.SwerveModuleBase
-
Sets the angle of the module.
- setRawSpeed(double) - Method in class com.mineinjava.quail.SwerveModuleBase
-
Sets the raw speed of the module.
- setRotationConstraints(ConstraintsPair) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the rotation constraints of the path follower.
- setRotationConstraints(ConstraintsPair) - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Set the rotation constraints for the path follower, used for all paths AFTER this call
- setSetpoint(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Configure setpoint for the PID calculations.
- setSetpointRange(double) - Method in class com.mineinjava.quail.util.MiniPID
-
Set a limit on how far the setpoint can be from the current position.
- setSlowDownDistance(double) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the distance from the last point that the robot will begin to slowdown.
- setSlowdownKP(double) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the kP of the slowdown distance.
- setSpeed(double) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the speed of the robot.
- setSpeed(double) - Method in class com.mineinjava.quail.SwerveModuleBase
-
Sets the speed of the module.
- setTranslationConstraints(ConstraintsPair) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the translation constraints of the path follower.
- setTranslationConstraints(ConstraintsPair) - Method in class com.mineinjava.quail.pathing.PathSequenceFollower
-
Set the translation constraints for the path follower, used for all paths AFTER this call
- setTurnController(MiniPID) - Method in class com.mineinjava.quail.pathing.PathFollower
-
Sets the turning PID controller of the robot.
- steeringRatio - Variable in class com.mineinjava.quail.SwerveModuleBase
- steeringVector - Variable in class com.mineinjava.quail.SwerveModuleBase
- subtract(double, double) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Subtracts the vector by the passed in vector.
- subtract(RobotMovement) - Method in class com.mineinjava.quail.RobotMovement
- subtract(Vec2d) - Method in class com.mineinjava.quail.util.geometry.Vec2d
-
Subtracts the vector by the passed in vector.
- SwerveDrive<T extends SwerveModuleBase> - Class in com.mineinjava.quail
- SwerveDrive(List<T>) - Constructor for class com.mineinjava.quail.SwerveDrive
-
Represents a swerve drive .
- SwerveDrive(List<T>, double) - Constructor for class com.mineinjava.quail.SwerveDrive
- SwerveModuleBase - Class in com.mineinjava.quail
- SwerveModuleBase(Vec2d, double, double) - Constructor for class com.mineinjava.quail.SwerveModuleBase
-
Represents a swerve module Designed to be inherited.
- SwerveModuleBase(Vec2d, double, double, boolean) - Constructor for class com.mineinjava.quail.SwerveModuleBase
- swerveModules - Variable in class com.mineinjava.quail.SwerveDrive
- SwerveOdometry - Class in com.mineinjava.quail.localization
-
Represents a swerve drive position on the field.
- SwerveOdometry(SwerveDrive) - Constructor for class com.mineinjava.quail.localization.SwerveOdometry
-
Instantiates the SwerveOdometry object
- SwerveOdometry(Vec2d[]) - Constructor for class com.mineinjava.quail.localization.SwerveOdometry
-
Instantiates the SwerveOdometry object
- SwerveOdometry(ArrayList<Vec2d>) - Constructor for class com.mineinjava.quail.localization.SwerveOdometry
-
Instantiates the SwerveOdometry object
- SwerveOdometry(List<Vec2d>) - Constructor for class com.mineinjava.quail.localization.SwerveOdometry
-
Instantiates the SwerveOdometry object
T
- theta - Variable in class com.mineinjava.quail.localization.SwerveOdometry
- times(double) - Method in class com.mineinjava.quail.util.geometry.Pose2d
- toString() - Method in class com.mineinjava.quail.util.geometry.Pose2d
- toString() - Method in class com.mineinjava.quail.util.geometry.Vec2d
- translation - Variable in class com.mineinjava.quail.RobotMovement
- TwoWheelLocalizer - Class in com.mineinjava.quail.localization
-
Localizer implementation for a two-wheel + gyro setup commonly seen in FTC
- TwoWheelLocalizer(List<Pose2d>) - Constructor for class com.mineinjava.quail.localization.TwoWheelLocalizer
U
- unaryMinus() - Method in class com.mineinjava.quail.util.geometry.Pose2d
- update() - Method in class com.mineinjava.quail.localization.TwoWheelLocalizer
-
Updates the robot's position on the field using the deadwheel positions.
- update() - Method in class com.mineinjava.quail.util.geometry.AccelerationLimitedDouble
-
Calculates a new output Value based on the time since the last update.
- update() - Method in class com.mineinjava.quail.util.geometry.AccelerationLimitedVector
-
Calculates a new output vector based on the time since the last update.
- update(double) - Method in class com.mineinjava.quail.util.geometry.AccelerationLimitedDouble
-
Updates the ideal Value and calculates a new output Value based on the time since the last update.
- update(Vec2d) - Method in class com.mineinjava.quail.util.geometry.AccelerationLimitedVector
-
Updates the ideal vector and calculates a new output vector based on the time since the last update.
- update(Vec2d, Vec2d, double, double, double) - Method in class com.mineinjava.quail.localization.KalmanFilterLocalizer
-
Updates the pose estimate.
- updateDeltaOdometry(double, double, double) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Updates the robot's position based on a change in x, y, and a theta.
- updateDeltaOdometry(Vec2d, double) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Updates the robot's position based on a change in x, y, (represented by a vector) and a theta.
- updateDeltaPoseEstimate(Vec2d) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Updates the robot's position based on a change in x, y (represented by a vector).
- updateOdometry(double, double, double) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Sets the robot's position to a specific x, y, and theta.
- updateOdometry(Vec2d) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Sets the robot's position to a specific x, y (represented by a vector).
- updateOdometry(Vec2d, double) - Method in class com.mineinjava.quail.localization.SwerveOdometry
-
Sets the robot's position to a specific x, y, (represented by a vector) and theta.
V
- valueOf(String) - Static method in enum class com.mineinjava.quail.pathing.SegmentType
-
Returns the enum constant of this class with the specified name.
- values() - Static method in enum class com.mineinjava.quail.pathing.SegmentType
-
Returns an array containing the constants of this enum class, in the order they are declared.
- vec() - Method in class com.mineinjava.quail.util.geometry.Pose2d
-
Converts x and y position to a vector Does not include heading.
- Vec2d - Class in com.mineinjava.quail.util.geometry
-
Represents a two-dimensional vector.
- Vec2d() - Constructor for class com.mineinjava.quail.util.geometry.Vec2d
-
Creates a unit vector pointing in the positive x direction.
- Vec2d(double) - Constructor for class com.mineinjava.quail.util.geometry.Vec2d
-
Creates a vector pointing in the positive x direction with the specified magnitude.
- Vec2d(double[]) - Constructor for class com.mineinjava.quail.util.geometry.Vec2d
-
Creates a vector from an array of coordinates.
- Vec2d(double, boolean) - Constructor for class com.mineinjava.quail.util.geometry.Vec2d
-
Creates a unit vector from a rotation.
- Vec2d(double, double) - Constructor for class com.mineinjava.quail.util.geometry.Vec2d
-
Creates a vector from x and y coordinates.
- Vec2d(double, double, boolean) - Constructor for class com.mineinjava.quail.util.geometry.Vec2d
-
Creates a vector from a rotation with a specified magnitude.
- vectorLastToCurrentPoint() - Method in class com.mineinjava.quail.pathing.Path
-
Returns a vector from the last point to the current point.
- vectorTo(Pose2d) - Method in class com.mineinjava.quail.util.geometry.Pose2d
-
Returns a vector from this Pose2d to another Pose2d
- vectorToCurrentPoint(Pose2d) - Method in class com.mineinjava.quail.pathing.Path
-
Returns a vector from the passed pose to the current point.
- vectorToNearestPoint(Pose2d, int) - Method in class com.mineinjava.quail.pathing.Path
-
Calculates a vector from (x,y) to the nearest point on the path.
X
- x - Variable in class com.mineinjava.quail.localization.SwerveOdometry
- x - Variable in class com.mineinjava.quail.util.geometry.Pose2d
- x - Variable in class com.mineinjava.quail.util.geometry.Vec2d
- XLock() - Method in class com.mineinjava.quail.SwerveModuleBase
-
"X-Locks" the modules.
- XLockModules() - Method in class com.mineinjava.quail.SwerveDrive
Y
- y - Variable in class com.mineinjava.quail.localization.SwerveOdometry
- y - Variable in class com.mineinjava.quail.util.geometry.Pose2d
- y - Variable in class com.mineinjava.quail.util.geometry.Vec2d
All Classes and Interfaces|All Packages|Constant Field Values