- acceleration(time) - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
- AccelRegression - Class in com.acmerobotics.roadrunner.tuning
-
Container for acceleration feedforward regression data. This data can be gathered through pretty much any motion
although it's standard to apply constant/step voltage/power.
- AccelRegression(timeSamples, positionSamples, powerSamples) - Constructor for class com.acmerobotics.roadrunner.tuning.AccelRegression
-
Container for acceleration feedforward regression data. This data can be gathered through pretty much any motion
although it's standard to apply constant/step voltage/power.
- AccelRegression(timeSamples, positionSamples) - Constructor for class com.acmerobotics.roadrunner.tuning.AccelRegression
-
Container for acceleration feedforward regression data. This data can be gathered through pretty much any motion
although it's standard to apply constant/step voltage/power.
- AccelRegression(timeSamples) - Constructor for class com.acmerobotics.roadrunner.tuning.AccelRegression
-
Container for acceleration feedforward regression data. This data can be gathered through pretty much any motion
although it's standard to apply constant/step voltage/power.
- AccelRegression() - Constructor for class com.acmerobotics.roadrunner.tuning.AccelRegression
-
Container for acceleration feedforward regression data. This data can be gathered through pretty much any motion
although it's standard to apply constant/step voltage/power.
- AccelRegression.AccelResult - Class in com.acmerobotics.roadrunner.tuning
-
Feedforward parameter estimates from the ramp regression and additional summary statistics
- AccelResult(kA, rSquare) - Constructor for class com.acmerobotics.roadrunner.tuning.AccelRegression.AccelResult
-
Feedforward parameter estimates from the ramp regression and additional summary statistics
- add(time, position, power) - Method in class com.acmerobotics.roadrunner.tuning.AccelRegression
-
Add a sample to the regression.
- add(time, position, power) - Method in class com.acmerobotics.roadrunner.tuning.RampRegression
-
Add a sample to the regression.
- addMarker(time, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a marker to the trajectory at
time
.
- addMarker(point, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a marker that will be triggered at the closest trajectory point to
point
.
- addMarker(callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a marker at the current position of the trajectory.
- angle() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- Angle - Class in com.acmerobotics.roadrunner.util
-
Various utilities for working with angles.
- appendAccelerationControl(accel, dt) - Method in class com.acmerobotics.roadrunner.profile.MotionProfileBuilder
-
Appends a constant-acceleration control for the provided duration.
- appendJerkControl(jerk, dt) - Method in class com.acmerobotics.roadrunner.profile.MotionProfileBuilder
-
Appends a constant-jerk control for the provided duration.
- appendProfile(profile) - Method in class com.acmerobotics.roadrunner.profile.MotionProfileBuilder
-
- calculateMotorFeedforward(vels, accels, kV, kA, kStatic) - Static method in class com.acmerobotics.roadrunner.kinematics.Kinematics
-
Computes the motor feedforward (i.e., open loop powers) for the given set of coefficients.
- calculateMotorFeedforward(vel, accel, kV, kA, kStatic) - Static method in class com.acmerobotics.roadrunner.kinematics.Kinematics
-
Computes the motor feedforward (i.e., open loop power) for the given set of coefficients.
- calculatePoseError(targetFieldPose, currentFieldPose) - Static method in class com.acmerobotics.roadrunner.kinematics.Kinematics
-
- com.acmerobotics.roadrunner.control - package com.acmerobotics.roadrunner.control
-
- com.acmerobotics.roadrunner.drive - package com.acmerobotics.roadrunner.drive
-
- com.acmerobotics.roadrunner.followers - package com.acmerobotics.roadrunner.followers
-
- com.acmerobotics.roadrunner.geometry - package com.acmerobotics.roadrunner.geometry
-
- com.acmerobotics.roadrunner.kinematics - package com.acmerobotics.roadrunner.kinematics
-
- com.acmerobotics.roadrunner.localization - package com.acmerobotics.roadrunner.localization
-
- com.acmerobotics.roadrunner.path - package com.acmerobotics.roadrunner.path
-
- com.acmerobotics.roadrunner.path.heading - package com.acmerobotics.roadrunner.path.heading
-
- com.acmerobotics.roadrunner.profile - package com.acmerobotics.roadrunner.profile
-
- com.acmerobotics.roadrunner.trajectory - package com.acmerobotics.roadrunner.trajectory
-
- com.acmerobotics.roadrunner.trajectory.constraints - package com.acmerobotics.roadrunner.trajectory.constraints
-
- com.acmerobotics.roadrunner.tuning - package com.acmerobotics.roadrunner.tuning
-
- com.acmerobotics.roadrunner.util - package com.acmerobotics.roadrunner.util
-
- Companion - Static variable in class com.acmerobotics.roadrunner.util.NanoClock
-
- component1() - Method in class com.acmerobotics.roadrunner.control.PIDCoefficients
-
proportional gain
- component1() - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
-
robot frame velocity
- component1() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- component1() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- component1() - Method in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
constant maximum velocity
- component1() - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
- component1() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
- component1() - Method in class com.acmerobotics.roadrunner.tuning.AccelRegression.AccelResult
-
- component1() - Method in class com.acmerobotics.roadrunner.tuning.RampRegression.RampResult
-
- component1() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
normalized direction vector of the GVF
- component2() - Method in class com.acmerobotics.roadrunner.control.PIDCoefficients
-
integral gain
- component2() - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
-
robot frame acceleration
- component2() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- component2() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- component2() - Method in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
constant maximum acceleration
- component2() - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
- component2() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
- component2() - Method in class com.acmerobotics.roadrunner.tuning.AccelRegression.AccelResult
-
- component2() - Method in class com.acmerobotics.roadrunner.tuning.RampRegression.RampResult
-
- component2() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
point on the path from the projection
- component3() - Method in class com.acmerobotics.roadrunner.control.PIDCoefficients
-
derivative gain
- component3() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- component3() - Method in class com.acmerobotics.roadrunner.tuning.RampRegression.RampResult
-
- component3() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
displacement along the path of
- component4() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
signed cross track error
- ConstantInterpolator - Class in com.acmerobotics.roadrunner.path.heading
-
Constant heading interpolator used for arbitrary holonomic translations.
- ConstantInterpolator(heading) - Constructor for class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
Constant heading interpolator used for arbitrary holonomic translations.
- contains(query) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- copy(kP, kI, kD) - Method in class com.acmerobotics.roadrunner.control.PIDCoefficients
-
- copy(vel, accel) - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
-
Signal indicating the commanded kinematic state of a drive.
- copy(x, y, heading) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- copy(x, y) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
Class for representing 2D vectors (x and y).
- copy(maxVel, maxAccel) - Method in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
Constant velocity and acceleration constraints.
- copy(point, callback) - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
Trajectory marker that is triggered when the trajectory passes the specified point.
- copy(time, callback) - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
Trajectory marker that is triggered when the specified time passes.
- copy(kA, rSquare) - Method in class com.acmerobotics.roadrunner.tuning.AccelRegression.AccelResult
-
Feedforward parameter estimates from the ramp regression and additional summary statistics
- copy(kV, kStatic, rSquare) - Method in class com.acmerobotics.roadrunner.tuning.RampRegression.RampResult
-
Feedforward parameter estimates from the ramp regression and additional summary statistics
- copy(vector, pathPoint, displacement, error) - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
Container for the direction of the GVF and intermediate values used in its computation.
- curve - Variable in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Base parametric curve
- deriv(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading derivative at the specified
s
.
- deriv(s) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading derivative at the specified
s
.
- deriv(s, t) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the derivative
s
units along the curve.
- deriv(s) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the derivative
s
units along the curve.
- deriv(s, t) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose derivative
s
units along the path.
- deriv(s) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose derivative
s
units along the path.
- deriv(s, t) - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
- deriv(s) - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
- deriv(t) - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
Returns the derivative of the polynomial at
t
.
- deriv() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
- distTo(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- div(scalar) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- div($receiver, pose) - Static method in class com.acmerobotics.roadrunner.geometry.Pose2dKt
-
- div(scalar) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- div($receiver, vector) - Static method in class com.acmerobotics.roadrunner.geometry.Vector2dKt
-
- dot(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- DoubleProgression - Class in com.acmerobotics.roadrunner.util
-
A progression of values of type Double
.
- DoubleProgression(start, end, step) - Constructor for class com.acmerobotics.roadrunner.util.DoubleProgression
-
A progression of values of type Double
.
- DoubleProgression.IteratorImpl - Class in com.acmerobotics.roadrunner.util
-
- DoubleProgressionKt - Class in com.acmerobotics.roadrunner.util
-
- Drive - Class in com.acmerobotics.roadrunner.drive
-
Abstraction for generic robot drive motion and localization. Robot poses are specified in a coordinate system with
positive x pointing forward, positive y pointing left, and positive heading measured counter-clockwise from the
x-axis.
- Drive() - Constructor for class com.acmerobotics.roadrunner.drive.Drive
-
Abstraction for generic robot drive motion and localization. Robot poses are specified in a coordinate system with
positive x pointing forward, positive y pointing left, and positive heading measured counter-clockwise from the
x-axis.
- DriveConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
This class describes general robot trajectory constraints. More specifically, for paths, the robot velocity,
robot acceleration, and robot angular velocity are limited. For point turns, the angular velocity and angular
acceleration are limited. If maxJerk or maxAngJerk are 0, acceleration-limited fallbacks will be used.
- DriveConstraints(maxVel, maxAccel, maxJerk, maxAngVel, maxAngAccel, maxAngJerk) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
This class describes general robot trajectory constraints. More specifically, for paths, the robot velocity,
robot acceleration, and robot angular velocity are limited. For point turns, the angular velocity and angular
acceleration are limited. If maxJerk or maxAngJerk are 0, acceleration-limited fallbacks will be used.
- DriveSignal - Class in com.acmerobotics.roadrunner.drive
-
Signal indicating the commanded kinematic state of a drive.
- DriveSignal(vel, accel) - Constructor for class com.acmerobotics.roadrunner.drive.DriveSignal
-
Signal indicating the commanded kinematic state of a drive.
- DriveSignal(vel) - Constructor for class com.acmerobotics.roadrunner.drive.DriveSignal
-
Signal indicating the commanded kinematic state of a drive.
- DriveSignal() - Constructor for class com.acmerobotics.roadrunner.drive.DriveSignal
-
Signal indicating the commanded kinematic state of a drive.
- duration() - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
-
Returns the duration of the motion profile.
- duration() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
- generateMotionProfile(start, goal, constraints, resolution) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a motion profile with dynamic maximum velocity and acceleration. Uses the algorithm described in
section 3.2 of
Sprunk2008.pdf. Warning:
Profiles may be generated incorrectly if the endpoint velocity/acceleration values preclude the obedience of the
motion constraints. To protect against this, verify the continuity of the generated profile or keep the start and
goal velocities at 0.
- generateMotionProfile(start, goal, constraints) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a motion profile with dynamic maximum velocity and acceleration. Uses the algorithm described in
section 3.2 of
Sprunk2008.pdf. Warning:
Profiles may be generated incorrectly if the endpoint velocity/acceleration values preclude the obedience of the
motion constraints. To protect against this, verify the continuity of the generated profile or keep the start and
goal velocities at 0.
- generateSimpleMotionProfile(start, goal, maxVel, maxAccel, maxJerk, overshoot) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a simple motion profile with constant
maxVel
,
maxAccel
, and
maxJerk
. If
maxJerk
is zero, an
acceleration-limited profile will be generated instead of a jerk-limited one. If constraints can't be obeyed,
there are two possible fallbacks: If
overshoot
is true, then two profiles will be concatenated (the first one
overshoots the goal and the second one reverses back to reach the goal). Otherwise, the highest order constraint
(e.g., max jerk for jerk-limited profiles) is repeatedly violated until the goal is achieved.
- generateSimpleMotionProfile(start, goal, maxVel, maxAccel, maxJerk) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a simple motion profile with constant
maxVel
,
maxAccel
, and
maxJerk
. If
maxJerk
is zero, an
acceleration-limited profile will be generated instead of a jerk-limited one. If constraints can't be obeyed,
there are two possible fallbacks: If
overshoot
is true, then two profiles will be concatenated (the first one
overshoots the goal and the second one reverses back to reach the goal). Otherwise, the highest order constraint
(e.g., max jerk for jerk-limited profiles) is repeatedly violated until the goal is achieved.
- generateSimpleMotionProfile(start, goal, maxVel, maxAccel) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a simple motion profile with constant
maxVel
,
maxAccel
, and
maxJerk
. If
maxJerk
is zero, an
acceleration-limited profile will be generated instead of a jerk-limited one. If constraints can't be obeyed,
there are two possible fallbacks: If
overshoot
is true, then two profiles will be concatenated (the first one
overshoots the goal and the second one reverses back to reach the goal). Otherwise, the highest order constraint
(e.g., max jerk for jerk-limited profiles) is repeatedly violated until the goal is achieved.
- generateSimpleTrajectory(path, driveConstraints, start, goal, temporalMarkers, spatialMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a simple constraint trajectory.
- generateSimpleTrajectory(path, driveConstraints, start, goal, temporalMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a simple constraint trajectory.
- generateSimpleTrajectory(path, driveConstraints, start, goal) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a simple constraint trajectory.
- generateSimpleTrajectory(path, driveConstraints, start) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a simple constraint trajectory.
- generateSimpleTrajectory(path, driveConstraints) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a simple constraint trajectory.
- generateTrajectory(path, trajectoryConstraints, start, goal, temporalMarkers, spatialMarkers, resolution) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a dynamic constraint trajectory.
- generateTrajectory(path, trajectoryConstraints, start, goal, temporalMarkers, spatialMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a dynamic constraint trajectory.
- generateTrajectory(path, trajectoryConstraints, start, goal, temporalMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a dynamic constraint trajectory.
- generateTrajectory(path, trajectoryConstraints, start, goal) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a dynamic constraint trajectory.
- generateTrajectory(path, trajectoryConstraints, start) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a dynamic constraint trajectory.
- generateTrajectory(path, trajectoryConstraints) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Generate a dynamic constraint trajectory.
- get(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading at the specified
s
.
- get(s) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading at the specified
s
.
- get(s, t) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the vector
s
units along the curve.
- get(s) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the vector
s
units along the curve.
- get(s, t) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose
s
units along the path.
- get(s) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose
s
units along the path.
- get(s, t) - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
- get(s) - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
- get(t) - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
Returns the value of the polynomial at
t
.
- get(s) - Method in class com.acmerobotics.roadrunner.profile.MotionConstraints
-
Returns the motion constraints
s
units along the profile.
- get(s) - Method in class com.acmerobotics.roadrunner.profile.MotionConstraints
-
- get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
-
- get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
-
- get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- get(pose, deriv, secondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
Returns the maximum velocity and acceleration for the given pose derivatives.
- get(pose, deriv, secondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.MecanumConstraints
-
Returns the maximum velocity and acceleration for the given pose derivatives.
- get(pose, deriv, secondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.SwerveConstraints
-
Returns the maximum velocity and acceleration for the given pose derivatives.
- get(pose, deriv, secondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.TankConstraints
-
Returns the maximum velocity and acceleration for the given pose derivatives.
- get(pose, deriv, secondDeriv) - Method in interface com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryConstraints
-
Returns the maximum velocity and acceleration for the given pose derivatives.
- get(time) - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
- get(x, y) - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField
-
Returns the normalized value of the vector field at the given point.
- getA() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getA() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getAccel() - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
-
robot frame acceleration
- getB() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getC() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getCallback() - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
- getCallback() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
- getClock() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
clock
- getClock() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
clock
- getConstraints() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
constraints
- getCurve() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Base parametric curve
- getCurve() - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
parametric curve
- getD() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getD2x() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
x second derivative
- getD2y() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
y second derivative
- getDisplacement() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
displacement along the path of
- getDt() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
-
time delta
- getDx() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
x derivative
- getDy() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
y derivative
- getE() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getEnd() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- getError() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
signed cross track error
- getExtended(x, y, projectGuess) - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField
-
Returns the normalized value of the vector field at the given point along with useful intermediate computations.
- getExternalHeading() - Method in class com.acmerobotics.roadrunner.drive.Drive
-
The robot's heading in radians as measured by an external sensor (e.g., IMU, gyroscope).
- getF() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getHeading() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- getHeading() - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
-
Returns the heading of the robot (usually from a gyroscope or IMU).
- getHeading() - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
heading to maintain
- getInterpolator() - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
heading interpolator
- getJ() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getLastError() - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Error computed in the last call to
update
.
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.GVFFollower
-
Robot pose error computed in the last
update
call.
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
Robot pose error computed in the last
update
call.
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
Robot pose error computed in the last
update
call.
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.RamseteFollower
-
Robot pose error computed in the last
update
call.
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
Robot pose error computed in the last
update
call.
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
Robot pose error computed in the last
update
call.
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.Drive
-
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
- getMarkers() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
- getModuleOrientations() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Returns the current module orientations in radians. Orientations should exactly match the order in
setModuleOrientations
.
- getPath() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
- getPath() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
path
- getPathPoint() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
point on the path from the projection
- getPoint() - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.drive.Drive
-
The robot's current pose estimate.
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive.MecanumLocalizer
-
Current robot pose estimate.
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive.SwerveLocalizer
-
Current robot pose estimate.
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.drive.TankDrive.TankLocalizer
-
Current robot pose estimate.
- getPoseEstimate() - Method in interface com.acmerobotics.roadrunner.localization.Localizer
-
Current robot pose estimate.
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
-
Current robot pose estimate.
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
-
Current robot pose estimate.
- getPoses() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
poses
- getProfile() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
motion profile
- getRawExternalHeading() - Method in class com.acmerobotics.roadrunner.drive.Drive
-
- getResolution() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
resolution used for path-based segments
- getReversed() - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
if true,
- getSegments() - Method in class com.acmerobotics.roadrunner.path.Path
-
list of path segments
- getStart() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
-
start motion state
- getStart() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- getStep() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- getTargetPosition() - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Target position (that is, the controller setpoint).
- getTime() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
- getTrackWidth() - Method in class com.acmerobotics.roadrunner.trajectory.constraints.TankConstraints
-
track width
- getTrajectory() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- getV() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getVector() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
normalized direction vector of the GVF
- getVel() - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
-
robot frame velocity
- getWheelPositions() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
Returns the positions of the wheels in linear distance units. Positions should exactly match the ordering in
setMotorPowers
.
- getWheelPositions() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Returns the positions of the wheels in linear distance units. Positions should exactly match the ordering in
setMotorPowers
.
- getWheelPositions() - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
Returns the positions of the wheels in linear distance units. Positions should exactly match the ordering in
setMotorPowers
.
- getWheelPositions() - Method in class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
-
Returns the positions of the tracking wheels in the desired distance units (not encoder counts!)
- getWheelPositions() - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
-
Returns the positions of the tracking wheels in the desired distance units (not encoder counts!)
- getX() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- getX() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- getX() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
X polynomial (i.e., x(t))
- getX() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
x position
- getX() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getY() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- getY() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- getY() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
Y polynomial (i.e., y(t))
- getY() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
y position
- GuidingVectorField - Class in com.acmerobotics.roadrunner.util
-
Guiding vector field for effective path following described in section III, eq. (9) of
1610.04391.pdf. Implementation note: 2D parametric curves are used to
describe paths instead of implicit curves of the form f(x,y) = 0 as described in the paper (which dramatically
affects the cross track error calculation).
- GuidingVectorField(path, kN, errorMapFunc) - Constructor for class com.acmerobotics.roadrunner.util.GuidingVectorField
-
Guiding vector field for effective path following described in section III, eq. (9) of
1610.04391.pdf. Implementation note: 2D parametric curves are used to
describe paths instead of implicit curves of the form f(x,y) = 0 as described in the paper (which dramatically
affects the cross track error calculation).
- GuidingVectorField.GVFResult - Class in com.acmerobotics.roadrunner.util
-
Container for the direction of the GVF and intermediate values used in its computation.
- GVFFollower - Class in com.acmerobotics.roadrunner.followers
-
- GVFFollower(constraints, admissibleError, kN, kOmega, errorMapFunc, clock) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
-
- GVFFollower(constraints, admissibleError, kN, kOmega, errorMapFunc) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
-
- GVFFollower(constraints, admissibleError, kN, kOmega) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
-
- GVFResult(vector, pathPoint, displacement, error) - Constructor for class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
Container for the direction of the GVF and intermediate values used in its computation.
- hashCode() - Method in class com.acmerobotics.roadrunner.control.PIDCoefficients
-
- hashCode() - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
-
- hashCode() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- hashCode() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- hashCode() - Method in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
- hashCode() - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
- hashCode() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
- hashCode() - Method in class com.acmerobotics.roadrunner.tuning.AccelRegression.AccelResult
-
- hashCode() - Method in class com.acmerobotics.roadrunner.tuning.RampRegression.RampResult
-
- hashCode() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- hashCode() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
- hasNext() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression.IteratorImpl
-
- HeadingInterpolator - Class in com.acmerobotics.roadrunner.path.heading
-
Interpolator for specifying the heading for holonomic paths.
- HeadingInterpolator() - Constructor for class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Interpolator for specifying the heading for holonomic paths.
- HolonomicPIDVAFollower - Class in com.acmerobotics.roadrunner.followers
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, the feedback is applied to the components of the robot's pose (x position, y position, and heading) to
determine the velocity correction. The feedforward components are instead applied at the wheel level.
- HolonomicPIDVAFollower(axialCoeffs, lateralCoeffs, headingCoeffs, admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, the feedback is applied to the components of the robot's pose (x position, y position, and heading) to
determine the velocity correction. The feedforward components are instead applied at the wheel level.
- HolonomicPIDVAFollower(axialCoeffs, lateralCoeffs, headingCoeffs, admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, the feedback is applied to the components of the robot's pose (x position, y position, and heading) to
determine the velocity correction. The feedforward components are instead applied at the wheel level.
- HolonomicPIDVAFollower(axialCoeffs, lateralCoeffs, headingCoeffs, admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, the feedback is applied to the components of the robot's pose (x position, y position, and heading) to
determine the velocity correction. The feedforward components are instead applied at the wheel level.
- HolonomicPIDVAFollower(axialCoeffs, lateralCoeffs, headingCoeffs) - Constructor for class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, the feedback is applied to the components of the robot's pose (x position, y position, and heading) to
determine the velocity correction. The feedforward components are instead applied at the wheel level.
- init(curve) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Initialize the interpolator with a
curve
.
- init(curve) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Initialize the interpolator with a
curve
.
- init(curve) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
Initialize the interpolator with a
curve
.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.kinematics.Kinematics
-
A collection of methods for various kinematics-related tasks.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
-
Mecanum drive kinematic equations. All wheel positions and velocities are given starting with front left and
proceeding counter-clockwise (i.e., front left, rear left, rear right, front right). Robot poses are specified in a
coordinate system with positive x pointing forward, positive y pointing left, and positive heading measured
counter-clockwise from the x-axis.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
-
Swerve drive kinematic equations. All wheel positions and velocities are given starting with front left and
proceeding counter-clockwise (i.e., front left, rear left, rear right, front right). Robot poses are specified in a
coordinate system with positive x pointing forward, positive y pointing left, and positive heading measured
counter-clockwise from the x-axis.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.kinematics.TankKinematics
-
Tank drive kinematic equations based upon the unicycle model. All wheel positions and velocities are given in
(left, right) tuples. Robot poses are specified in a coordinate system with positive x pointing forward, positive y
pointing left, and positive heading measured counter-clockwise from the x-axis.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Motion profile generator with arbitrary start and end motion states and either dynamic constraints or jerk limiting.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
-
Trajectory generator for creating trajectories with dynamic and static constraints from paths.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.trajectory.TrajectoryLoader
-
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.util.Angle
-
Various utilities for working with angles.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.util.MathUtil
-
Various math utilities.
- internalDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
- internalDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
-
- internalDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
- internalDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
- internalDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
- internalDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- internalGet$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
- internalGet$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
-
- internalGet$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
- internalGet$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
- internalGet$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
- internalGet$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalGet$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- internalSecondDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
- internalSecondDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
-
- internalSecondDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
- internalSecondDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
- internalSecondDeriv$module(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
- internalSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- internalThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- internalUpdate(currentPose) - Method in class com.acmerobotics.roadrunner.followers.GVFFollower
-
- internalUpdate(currentPose) - Method in class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
- internalUpdate(currentPose) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
- internalUpdate(currentPose) - Method in class com.acmerobotics.roadrunner.followers.RamseteFollower
-
- internalUpdate(currentPose) - Method in class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
- internalUpdate(currentPose) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- isEmpty() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- isFollowing() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
Returns true if the current path has finished executing.
- isFollowing() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
Returns true if the current trajectory has finished executing.
- items() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- iterator() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- MathUtil - Class in com.acmerobotics.roadrunner.util
-
Various math utilities.
- MathUtilKt - Class in com.acmerobotics.roadrunner.util
-
- maxAccel - Variable in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
constant maximum acceleration
- maxAccel - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum robot acceleration
- maxAngAccel - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum angular acceleration
- maxAngJerk - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum angular jerk
- maxAngVel - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum angular velocity
- maxJerk - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum robot jerk
- maxVel - Variable in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
constant maximum velocity
- maxVel - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum robot velocity
- MecanumConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- MecanumConstraints(baseConstraints, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MecanumConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- MecanumConstraints(baseConstraints, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MecanumConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- MecanumDrive - Class in com.acmerobotics.roadrunner.drive
-
- MecanumDrive(kV, kA, kStatic, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- MecanumDrive(kV, kA, kStatic, trackWidth) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- MecanumDrive.MecanumLocalizer - Class in com.acmerobotics.roadrunner.drive
-
Default localizer for mecanum drives based on the drive encoders and (optionally) a heading sensor.
- MecanumKinematics - Class in com.acmerobotics.roadrunner.kinematics
-
Mecanum drive kinematic equations. All wheel positions and velocities are given starting with front left and
proceeding counter-clockwise (i.e., front left, rear left, rear right, front right). Robot poses are specified in a
coordinate system with positive x pointing forward, positive y pointing left, and positive heading measured
counter-clockwise from the x-axis.
- MecanumLocalizer(drive, useExternalHeading) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive.MecanumLocalizer
-
Default localizer for mecanum drives based on the drive encoders and (optionally) a heading sensor.
- MecanumLocalizer(drive) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive.MecanumLocalizer
-
Default localizer for mecanum drives based on the drive encoders and (optionally) a heading sensor.
- minus(other) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- minus(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- minus(offset) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- minus($receiver, progression) - Static method in class com.acmerobotics.roadrunner.util.DoubleProgressionKt
-
- MotionConstraints - Class in com.acmerobotics.roadrunner.profile
-
Motion profile motion constraints.
- MotionConstraints() - Constructor for class com.acmerobotics.roadrunner.profile.MotionConstraints
-
Motion profile motion constraints.
- MotionProfile - Class in com.acmerobotics.roadrunner.profile
-
Trapezoidal motion profile composed of motion segments.
- MotionProfile(segments) - Constructor for class com.acmerobotics.roadrunner.profile.MotionProfile
-
Trapezoidal motion profile composed of motion segments.
- MotionProfileBuilder - Class in com.acmerobotics.roadrunner.profile
-
Easy-to-use builder for creating motion profiles.
- MotionProfileBuilder(start) - Constructor for class com.acmerobotics.roadrunner.profile.MotionProfileBuilder
-
Easy-to-use builder for creating motion profiles.
- MotionProfileGenerator - Class in com.acmerobotics.roadrunner.profile
-
Motion profile generator with arbitrary start and end motion states and either dynamic constraints or jerk limiting.
- MotionSegment - Class in com.acmerobotics.roadrunner.profile
-
Segment of a motion profile with constant acceleration.
- MotionSegment(start, dt) - Constructor for class com.acmerobotics.roadrunner.profile.MotionSegment
-
Segment of a motion profile with constant acceleration.
- MotionState - Class in com.acmerobotics.roadrunner.profile
-
Kinematic state of a motion profile at any given time.
- MotionState(x, v, a, j) - Constructor for class com.acmerobotics.roadrunner.profile.MotionState
-
Kinematic state of a motion profile at any given time.
- MotionState(x, v, a) - Constructor for class com.acmerobotics.roadrunner.profile.MotionState
-
Kinematic state of a motion profile at any given time.
- MotionState(x, v) - Constructor for class com.acmerobotics.roadrunner.profile.MotionState
-
Kinematic state of a motion profile at any given time.
- paramDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- paramDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- ParametricCurve - Class in com.acmerobotics.roadrunner.path
-
Parametric curve with two components (x and y). These curves are reparametrized from an internal parameter (t) to the
arc length parameter (s).
- ParametricCurve() - Constructor for class com.acmerobotics.roadrunner.path.ParametricCurve
-
Parametric curve with two components (x and y). These curves are reparametrized from an internal parameter (t) to the
arc length parameter (s).
- paramSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- paramSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- paramThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- paramThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- path - Variable in class com.acmerobotics.roadrunner.followers.PathFollower
-
- Path - Class in com.acmerobotics.roadrunner.path
-
Path composed of a list of parametric curves and heading interpolators.
- Path(segments) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
Path composed of a list of parametric curves and heading interpolators.
- Path(segment) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
- PathBuilder - Class in com.acmerobotics.roadrunner.path
-
Easy-to-use builder for creating
class Path
instances.
- PathBuilder(startPose) - Constructor for class com.acmerobotics.roadrunner.path.PathBuilder
-
- PathBuilder(path, s) - Constructor for class com.acmerobotics.roadrunner.path.PathBuilder
-
- PathFollower - Class in com.acmerobotics.roadrunner.followers
-
Generic
class Path
follower for time-independent pose reference tracking.
- PathFollower(admissibleError, clock) - Constructor for class com.acmerobotics.roadrunner.followers.PathFollower
-
Generic
class Path
follower for time-independent pose reference tracking.
- PathFollower(admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.PathFollower
-
Generic
class Path
follower for time-independent pose reference tracking.
- PathSegment - Class in com.acmerobotics.roadrunner.path
-
Path segment composed of a parametric curve and heading interpolator.
- PathSegment(curve, interpolator, reversed) - Constructor for class com.acmerobotics.roadrunner.path.PathSegment
-
Path segment composed of a parametric curve and heading interpolator.
- PathSegment(curve, interpolator) - Constructor for class com.acmerobotics.roadrunner.path.PathSegment
-
Path segment composed of a parametric curve and heading interpolator.
- PathSegment(curve) - Constructor for class com.acmerobotics.roadrunner.path.PathSegment
-
Path segment composed of a parametric curve and heading interpolator.
- PIDCoefficients - Class in com.acmerobotics.roadrunner.control
-
- PIDCoefficients(kP, kI, kD) - Constructor for class com.acmerobotics.roadrunner.control.PIDCoefficients
-
- PIDCoefficients() - Constructor for class com.acmerobotics.roadrunner.control.PIDCoefficients
-
- PIDFController - Class in com.acmerobotics.roadrunner.control
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV, kA, kStatic, kF, clock) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV, kA, kStatic, kF) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV, kA, kStatic) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV, kA) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- plus(other) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- plus(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- plus(other) - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
-
Returns a new motion profile with
other
concatenated.
- plus(offset) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- plus($receiver, progression) - Static method in class com.acmerobotics.roadrunner.util.DoubleProgressionKt
-
- pos() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
- Pose2d - Class in com.acmerobotics.roadrunner.geometry
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(x, y, heading) - Constructor for class com.acmerobotics.roadrunner.geometry.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(x, y) - Constructor for class com.acmerobotics.roadrunner.geometry.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(x) - Constructor for class com.acmerobotics.roadrunner.geometry.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d() - Constructor for class com.acmerobotics.roadrunner.geometry.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(pos, heading) - Constructor for class com.acmerobotics.roadrunner.geometry.Pose2d
-
- Pose2dKt - Class in com.acmerobotics.roadrunner.geometry
-
- project(queryPoint, projectGuess) - Method in class com.acmerobotics.roadrunner.path.Path
-
Project
queryPoint
onto the current path using the iterative method described
here.
- projectOnto(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- save(file) - Method in class com.acmerobotics.roadrunner.tuning.AccelRegression
-
Save the data to a CSV file for debugging or additional analysis.
- save(file) - Method in class com.acmerobotics.roadrunner.tuning.RampRegression
-
Save the data to a CSV file for debugging or additional analysis.
- saveConfig(trajectoryConfig, file) - Static method in class com.acmerobotics.roadrunner.trajectory.TrajectoryLoader
-
- secondDeriv(s, t) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading second derivative at the specified
s
.
- secondDeriv(s) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading second derivative at the specified
s
.
- secondDeriv(s, t) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the second derivative
s
units along the curve.
- secondDeriv(s) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the second derivative
s
units along the curve.
- secondDeriv(s, t) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose second derivative
s
units along the path.
- secondDeriv(s) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose second derivative
s
units along the path.
- secondDeriv(s, t) - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
- secondDeriv(s) - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
- secondDeriv(t) - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
Returns the second derivative of the polynomial at
t
.
- secondDeriv() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Waypoint
-
- seconds() - Method in class com.acmerobotics.roadrunner.util.NanoClock
-
Returns the number of seconds since an arbitrary (yet consistent) origin.
- setCurve(p) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Base parametric curve
- setDrivePower(drivePower) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
Sets the current commanded drive state of the robot. Feedforward is
not applied to
drivePower
.
- setDrivePower(drivePower) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
Sets the current commanded drive state of the robot. Feedforward is
not applied to
drivePower
.
- setDrivePower(drivePower) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Sets the current commanded drive state of the robot. Feedforward is
not applied to
drivePower
.
- setDrivePower(drivePower) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
Sets the current commanded drive state of the robot. Feedforward is
not applied to
drivePower
.
- setDriveSignal(driveSignal) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
Sets the current commanded drive state of the robot. Feedforward is applied to
driveSignal
before it reaches
the motors.
- setDriveSignal(driveSignal) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
Sets the current commanded drive state of the robot. Feedforward is applied to
driveSignal
before it reaches
the motors.
- setDriveSignal(driveSignal) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Sets the current commanded drive state of the robot. Feedforward is applied to
driveSignal
before it reaches
the motors.
- setDriveSignal(driveSignal) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
Sets the current commanded drive state of the robot. Feedforward is applied to
driveSignal
before it reaches
the motors.
- setExternalHeading(value) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
The robot's heading in radians as measured by an external sensor (e.g., IMU, gyroscope).
- setInputBounds(min, max) - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Sets bound on the input of the controller. The min and max values are considered modularly-equivalent (that is,
the input wraps around).
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.GVFFollower
-
Robot pose error computed in the last
update
call.
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
Robot pose error computed in the last
update
call.
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
Robot pose error computed in the last
update
call.
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.RamseteFollower
-
Robot pose error computed in the last
update
call.
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
Robot pose error computed in the last
update
call.
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
Robot pose error computed in the last
update
call.
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
- setModuleOrientations(frontLeft, rearLeft, rearRight, frontRight) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Sets the module orientations. All values are in radians.
- setMotorPowers(frontLeft, rearLeft, rearRight, frontRight) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
Sets the following motor powers (normalized voltages). All arguments are on the interval [-1.0, 1.0]
.
- setMotorPowers(frontLeft, rearLeft, rearRight, frontRight) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Sets the following motor powers (normalized voltages). All arguments are on the interval [-1.0, 1.0]
.
- setMotorPowers(left, right) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
Sets the following motor powers (normalized voltages). All arguments are on the interval [-1.0, 1.0]
.
- setOutputBounds(min, max) - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Sets bounds on the output of the controller.
- setPath(p) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
The robot's current pose estimate.
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive.MecanumLocalizer
-
Current robot pose estimate.
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive.SwerveLocalizer
-
Current robot pose estimate.
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.drive.TankDrive.TankLocalizer
-
Current robot pose estimate.
- setPoseEstimate(p) - Method in interface com.acmerobotics.roadrunner.localization.Localizer
-
Current robot pose estimate.
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
-
Current robot pose estimate.
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
-
Current robot pose estimate.
- setReversed(reversed) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Sets the robot travel direction.
- setReversed(reversed) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Sets the robot travel direction.
- setTargetPosition(p) - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Target position (that is, the controller setpoint).
- setTrajectory(p) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- SimpleMotionConstraints - Class in com.acmerobotics.roadrunner.profile
-
Constant velocity and acceleration constraints.
- SimpleMotionConstraints(maxVel, maxAccel) - Constructor for class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
Constant velocity and acceleration constraints.
- SimpleTrajectoryBuilder - Class in com.acmerobotics.roadrunner.trajectory
-
Builder for trajectories with static constraints.
- SimpleTrajectoryBuilder(startPose, driveConstraints, start) - Constructor for class com.acmerobotics.roadrunner.trajectory.SimpleTrajectoryBuilder
-
Create a builder from a start pose and motion state. This is the recommended constructor for creating
trajectories from rest.
- SimpleTrajectoryBuilder(startPose, driveConstraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.SimpleTrajectoryBuilder
-
Create a builder from a start pose and motion state. This is the recommended constructor for creating
trajectories from rest.
- SimpleTrajectoryBuilder(trajectory, t, driveConstraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.SimpleTrajectoryBuilder
-
Create a builder from an active trajectory. This is useful for interrupting a live trajectory and smoothly
transitioning to a new one.
- SimpleTrajectoryBuilderKt - Class in com.acmerobotics.roadrunner.trajectory
-
- solveQuadratic(a, b, c) - Static method in class com.acmerobotics.roadrunner.util.MathUtil
-
Returns the real solutions to the quadratic ax^2 + bx + c.
- SpatialMarker - Class in com.acmerobotics.roadrunner.trajectory
-
Trajectory marker that is triggered when the trajectory passes the specified point.
- SpatialMarker(point, callback) - Constructor for class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
Trajectory marker that is triggered when the trajectory passes the specified point.
- SplineInterpolator - Class in com.acmerobotics.roadrunner.path.heading
-
Spline heading interpolator for transitioning smoothly between headings without violating continuity (and hence
allowing for integration into longer profiles).
- SplineInterpolator(startHeading, endHeading) - Constructor for class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Spline heading interpolator for transitioning smoothly between headings without violating continuity (and hence
allowing for integration into longer profiles).
- splineTo(end, interpolator) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a spline segment.
- splineTo(end) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a spline segment.
- splineTo(pose, interpolator) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a spline segment.
- splineTo(pose) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a spline segment.
- split(sep) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- start() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the start heading.
- start() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the start vector.
- start() - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the start pose.
- start() - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
Returns the start pose.
- start() - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
-
- start() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
- startDeriv() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the start heading derivative.
- startDeriv() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the start derivative.
- startDeriv() - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the start pose derivative.
- startDeriv() - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
Returns the start pose derivative.
- startSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the start heading second derivative.
- startSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the start second derivative.
- startSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the start pose second derivative.
- startSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.PathSegment
-
Returns the start pose second derivative.
- startThirdDeriv() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the start third derivative.
- strafeLeft(distance) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a segment that strafes left in the robot reference frame.
- strafeLeft(distance) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a segment that strafes left in the robot reference frame.
- strafeRight(distance) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a segment that strafes right in the robot reference frame.
- strafeRight(distance) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a segment that strafes right in the robot reference frame.
- strafeTo(end) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a strafe path segment.
- strafeTo(pos) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
-
Adds a strafe path segment.
- SwerveConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- SwerveConstraints(baseConstraints, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.SwerveConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- SwerveConstraints(baseConstraints, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.SwerveConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- SwerveDrive - Class in com.acmerobotics.roadrunner.drive
-
- SwerveDrive(kV, kA, kStatic, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- SwerveDrive(kV, kA, kStatic, trackWidth) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- SwerveDrive.SwerveLocalizer - Class in com.acmerobotics.roadrunner.drive
-
Default localizer for swerve drives based on the drive encoder positions, module orientations, and (optionally) a
heading sensor.
- SwerveKinematics - Class in com.acmerobotics.roadrunner.kinematics
-
Swerve drive kinematic equations. All wheel positions and velocities are given starting with front left and
proceeding counter-clockwise (i.e., front left, rear left, rear right, front right). Robot poses are specified in a
coordinate system with positive x pointing forward, positive y pointing left, and positive heading measured
counter-clockwise from the x-axis.
- SwerveLocalizer(drive, useExternalHeading) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive.SwerveLocalizer
-
Default localizer for swerve drives based on the drive encoder positions, module orientations, and (optionally) a
heading sensor.
- SwerveLocalizer(drive) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive.SwerveLocalizer
-
Default localizer for swerve drives based on the drive encoder positions, module orientations, and (optionally) a
heading sensor.
- system() - Method in class com.acmerobotics.roadrunner.util.NanoClock.Companion
-
- system() - Static method in class com.acmerobotics.roadrunner.util.NanoClock
-
- tangentAngle(s, t) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the angle of the tangent line
s
units along the curve.
- tangentAngle(s) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the angle of the tangent line
s
units along the curve.
- tangentAngleDeriv(s, t) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the derivative of the tangent angle
s
units along the curve.
- tangentAngleDeriv(s) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the derivative of the tangent angle
s
units along the curve.
- tangentAngleSecondDeriv(s, t) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the second derivative of the tangent angle
s
units along the curve.
- tangentAngleSecondDeriv(s) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the second derivative of the tangent angle
s
units along the curve.
- TangentInterpolator - Class in com.acmerobotics.roadrunner.path.heading
-
Tangent (system) interpolator for tank/differential and other nonholonomic drives.
- TangentInterpolator() - Constructor for class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
Tangent (system) interpolator for tank/differential and other nonholonomic drives.
- TankConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
Tank-specific drive constraints that also limit maximum wheel velocities.
- TankConstraints(baseConstraints, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.TankConstraints
-
Tank-specific drive constraints that also limit maximum wheel velocities.
- TankDrive - Class in com.acmerobotics.roadrunner.drive
-
This class provides the basic functionality of a tank/differential drive using
class TankKinematics
.
- TankDrive(kV, kA, kStatic, trackWidth) - Constructor for class com.acmerobotics.roadrunner.drive.TankDrive
-
This class provides the basic functionality of a tank/differential drive using
class TankKinematics
.
- TankDrive.TankLocalizer - Class in com.acmerobotics.roadrunner.drive
-
Default localizer for tank drives based on the drive encoders and (optionally) a heading sensor.
- TankKinematics - Class in com.acmerobotics.roadrunner.kinematics
-
Tank drive kinematic equations based upon the unicycle model. All wheel positions and velocities are given in
(left, right) tuples. Robot poses are specified in a coordinate system with positive x pointing forward, positive y
pointing left, and positive heading measured counter-clockwise from the x-axis.
- TankLocalizer(drive, useExternalHeading) - Constructor for class com.acmerobotics.roadrunner.drive.TankDrive.TankLocalizer
-
Default localizer for tank drives based on the drive encoders and (optionally) a heading sensor.
- TankLocalizer(drive) - Constructor for class com.acmerobotics.roadrunner.drive.TankDrive.TankLocalizer
-
Default localizer for tank drives based on the drive encoders and (optionally) a heading sensor.
- TankPIDVAFollower - Class in com.acmerobotics.roadrunner.followers
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, one feedback loop controls the path displacement (that is, x in the robot reference frame), and
another feedback loop to minimize cross track (lateral) error via heading correction (overall, very similar to
class HolonomicPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(axialCoeffs, crossTrackCoeffs, admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, one feedback loop controls the path displacement (that is, x in the robot reference frame), and
another feedback loop to minimize cross track (lateral) error via heading correction (overall, very similar to
class HolonomicPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(axialCoeffs, crossTrackCoeffs, admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, one feedback loop controls the path displacement (that is, x in the robot reference frame), and
another feedback loop to minimize cross track (lateral) error via heading correction (overall, very similar to
class HolonomicPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(axialCoeffs, crossTrackCoeffs, admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, one feedback loop controls the path displacement (that is, x in the robot reference frame), and
another feedback loop to minimize cross track (lateral) error via heading correction (overall, very similar to
class HolonomicPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(axialCoeffs, crossTrackCoeffs) - Constructor for class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More
specifically, one feedback loop controls the path displacement (that is, x in the robot reference frame), and
another feedback loop to minimize cross track (lateral) error via heading correction (overall, very similar to
class HolonomicPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TemporalMarker - Class in com.acmerobotics.roadrunner.trajectory
-
Trajectory marker that is triggered when the specified time passes.
- TemporalMarker(time, callback) - Constructor for class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
Trajectory marker that is triggered when the specified time passes.
- thirdDeriv(s, t) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the third derivative
s
units along the curve.
- thirdDeriv(s) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the third derivative
s
units along the curve.
- thirdDeriv(t) - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
Returns the third derivative of the polynomial at
t
.
- ThreeTrackingWheelLocalizer - Class in com.acmerobotics.roadrunner.localization
-
Localizer based on three unpowered tracking omni wheels.
- ThreeTrackingWheelLocalizer(wheelPositions, wheelOrientations) - Constructor for class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
-
Localizer based on three unpowered tracking omni wheels.
- times(scalar) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- times($receiver, pose) - Static method in class com.acmerobotics.roadrunner.geometry.Pose2dKt
-
- times(scalar) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- times($receiver, vector) - Static method in class com.acmerobotics.roadrunner.geometry.Vector2dKt
-
- toString() - Method in class com.acmerobotics.roadrunner.control.PIDCoefficients
-
- toString() - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
-
- toString() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
-
- toString() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
-
- toString() - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- toString() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- toString() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
-
- toString() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
-
- toString() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- toString() - Method in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
- toString() - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
-
- toString() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
-
- toString() - Method in class com.acmerobotics.roadrunner.tuning.AccelRegression.AccelResult
-
- toString() - Method in class com.acmerobotics.roadrunner.tuning.RampRegression.RampResult
-
- toString() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
-
- toString() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
-
- toTrajectory() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
- trajectory - Variable in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- Trajectory - Class in com.acmerobotics.roadrunner.trajectory
-
- Trajectory(path, profile, markers) - Constructor for class com.acmerobotics.roadrunner.trajectory.Trajectory
-
- Trajectory(path, profile) - Constructor for class com.acmerobotics.roadrunner.trajectory.Trajectory
-
- TrajectoryBuilder - Class in com.acmerobotics.roadrunner.trajectory
-
Builder for trajectories with dynamic constraints.
- TrajectoryBuilder(startPose, trajectoryConstraints, start, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Create a builder from a start pose and motion state. This is the recommended constructor for creating
trajectories from rest.
- TrajectoryBuilder(startPose, trajectoryConstraints, start) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Create a builder from a start pose and motion state. This is the recommended constructor for creating
trajectories from rest.
- TrajectoryBuilder(startPose, trajectoryConstraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Create a builder from a start pose and motion state. This is the recommended constructor for creating
trajectories from rest.
- TrajectoryBuilder(trajectory, t, trajectoryConstraints, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Create a builder from an active trajectory. This is useful for interrupting a live trajectory and smoothly
transitioning to a new one.
- TrajectoryBuilder(trajectory, t, trajectoryConstraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Create a builder from an active trajectory. This is useful for interrupting a live trajectory and smoothly
transitioning to a new one.
- TrajectoryBuilderKt - Class in com.acmerobotics.roadrunner.trajectory
-
- TrajectoryConfig - Class in com.acmerobotics.roadrunner.trajectory
-
Basic trajectory configuration intended for serialization. Intentionally more simplistic and less flexible than
class BaseTrajectoryBuilder
.
- TrajectoryConfig(poses, constraints, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
Basic trajectory configuration intended for serialization. Intentionally more simplistic and less flexible than
class BaseTrajectoryBuilder
.
- TrajectoryConfig(poses, constraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
Basic trajectory configuration intended for serialization. Intentionally more simplistic and less flexible than
class BaseTrajectoryBuilder
.
- TrajectoryConstraints - Interface in com.acmerobotics.roadrunner.trajectory.constraints
-
Trajectory-specific constraints for motion profile generation.
- TrajectoryFollower - Class in com.acmerobotics.roadrunner.followers
-
- TrajectoryFollower(admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryFollower(admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryFollower(admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryFollower() - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryGenerator - Class in com.acmerobotics.roadrunner.trajectory
-
Trajectory generator for creating trajectories with dynamic and static constraints from paths.
- TrajectoryLoader - Class in com.acmerobotics.roadrunner.trajectory
-
- TwoTrackingWheelLocalizer - Class in com.acmerobotics.roadrunner.localization
-
Localizer based on two unpowered tracking omni wheels and an orientation sensor.
- TwoTrackingWheelLocalizer(wheelPositions, wheelOrientations) - Constructor for class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
-
Localizer based on two unpowered tracking omni wheels and an orientation sensor.