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

<

<no name provided>() - Static method in class com.acmerobotics.roadrunner.profile.AccelerationConstraintKt
Motion profile acceleration constraint.
<no name provided>() - Static method in class com.acmerobotics.roadrunner.profile.VelocityConstraintKt
Motion profile velocity constraint.
<no name provided>() - Static method in class com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraintKt
Motion profile acceleration constraint.
<no name provided>() - Static method in class com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraintKt
Motion profile velocity constraint.
<no name provided>() - Static method in class com.acmerobotics.roadrunner.trajectory.DisplacementProducerKt
SAM interface that produces a marker absolute displacement offset from the trajectory length.
<no name provided>() - Static method in class com.acmerobotics.roadrunner.trajectory.MarkerCallbackKt
SAM interface for marker callbacks.
<no name provided>() - Static method in class com.acmerobotics.roadrunner.trajectory.TimeProducerKt
SAM interface that produces a marker absolute time offset from the trajectory duration.

A

acceleration(time) - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
 
AccelerationConstraint - Interface in com.acmerobotics.roadrunner.profile
 
AccelerationConstraintKt - Class in com.acmerobotics.roadrunner.profile
 
addDisplacementMarker(callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker at the current position of the trajectory.
addDisplacementMarker(displacement, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker to the trajectory at displacement.
addDisplacementMarker(scale, offset, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker to the trajectory at scale * path length + offset.
addDisplacementMarker(displacement, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker to the trajectory at displacement evaluated with path length.
addSpatialMarker(point, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker that will be triggered at the closest trajectory point to point.
addTemporalMarker(time, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker to the trajectory at time.
addTemporalMarker(scale, offset, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker to the trajectory at scale * trajectory duration + offset.
addTemporalMarker(time, callback) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a marker to the trajectory at time evaluated with the trajectory duration.
angle() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 
Angle - Class in com.acmerobotics.roadrunner.util
Various utilities for working with angles.
angleBetween(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 
AngularVelocityConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Constraint limiting angular velocity.
AngularVelocityConstraint(maxAngularVel) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.AngularVelocityConstraint
Constraint limiting angular velocity.
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
Appends a class MotionProfile to the current queue of control actions.

B

back(distance) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a line straight backward.
back(distance) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a line straight backward.
back(distance, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a line straight backward.
BaseTrajectoryBuilder<T extends BaseTrajectoryBuilder<T>> - Class in com.acmerobotics.roadrunner.trajectory
Easy-to-use builder for creating class Trajectory instances.
BaseTrajectoryBuilder(startPose, startTangent, trajectory, t) - Constructor for class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Easy-to-use builder for creating class Trajectory instances.
build() - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Constructs the class Path instance.
build() - Method in class com.acmerobotics.roadrunner.profile.MotionProfileBuilder
Constructs and returns the class MotionProfile instance.
build() - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Constructs the class Trajectory instance.
buildTrajectory(path, temporalMarkers, displacementMarkers, spatialMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Build a trajectory from path.
buildTrajectory(path, temporalMarkers, displacementMarkers, spatialMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.SimpleTrajectoryBuilder
Build a trajectory from path.
buildTrajectory(path, temporalMarkers, displacementMarkers, spatialMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Build a trajectory from path.

C

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
Returns the error between targetFieldPose and currentFieldPose.
ceilIndex(query) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
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.config - package com.acmerobotics.roadrunner.trajectory.config
 
com.acmerobotics.roadrunner.trajectory.constraints - package com.acmerobotics.roadrunner.trajectory.constraints
 
com.acmerobotics.roadrunner.util - package com.acmerobotics.roadrunner.util
 
Companion - Static variable in class com.acmerobotics.roadrunner.geometry.Vector2d
 
Companion - Static variable in class com.acmerobotics.roadrunner.util.DoubleProgression
 
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.trajectory.config.TrajectoryConfig
 
component1() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
component1() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component1() - Method in class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
 
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.trajectory.TrajectoryMarker
 
component1() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
component1() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
normalized direction vector of the GVF
component10() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
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.trajectory.config.TrajectoryConfig
 
component2() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
component2() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component2() - Method in class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
 
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.trajectory.TrajectoryMarker
 
component2() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
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.trajectory.config.TrajectoryConfig
 
component3() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
component3() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component3() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
component3() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
displacement along the path of
component4() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
component4() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
component4() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component4() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
signed cross track error
component5() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component6() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component7() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component8() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
component9() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
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
Proportional, integral, and derivative (PID) gains used by class PIDFController.
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(startPose, startTangent, waypoints, resolution) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
Configuration describing a basic trajectory (a simpler frontend alternative to class BaseTrajectoryBuilder).
copy(position, heading, tangent, interpolationType) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
Description of a single segment of a composite trajectory.
copy(maxVel, maxAccel, maxAngVel, maxAngAccel, robotLength, robotWidth, driveType, trackWidth, wheelBase, lateralMultiplier) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
Configuration describing constraints and other robot-specific parameters that are shared by a group of trajectories.
copy(producer, callback) - Method in class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
Trajectory marker that is triggered when the specified displacement passes.
copy(point, callback) - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
Trajectory marker that is triggered when the trajectory passes the specified point.
copy(producer, callback) - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
Trajectory marker that is triggered when the specified time passes.
copy(time, callback) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryMarker
Trajectory marker that is triggered when the specified time passes.
copy(start, step, size) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
A progression of values of type Double.
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

D

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.Knot
 
DisplacementMarker - Class in com.acmerobotics.roadrunner.trajectory
Trajectory marker that is triggered when the specified displacement passes.
DisplacementMarker(producer, callback) - Constructor for class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
Trajectory marker that is triggered when the specified displacement passes.
DisplacementProducer - Interface in com.acmerobotics.roadrunner.trajectory
 
DisplacementProducerKt - Class in com.acmerobotics.roadrunner.trajectory
 
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, step, size) - Constructor for class com.acmerobotics.roadrunner.util.DoubleProgression
A progression of values of type Double.
DoubleProgression.Companion - Class in com.acmerobotics.roadrunner.util
 
DoubleProgression.IteratorImpl - Class in com.acmerobotics.roadrunner.util
Iterator implementation for class DoubleProgression.
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.
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
 

E

elapsedTime() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Returns the elapsed time since the last followTrajectory call.
EmptyPathSegmentException - Exception in com.acmerobotics.roadrunner.path
Exception thrown when empty path segments are requested.
EmptyPathSegmentException() - Constructor for exception com.acmerobotics.roadrunner.path.EmptyPathSegmentException
Exception thrown when empty path segments are requested.
end() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
Returns the end heading.
end() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
Returns the end vector.
end() - Method in class com.acmerobotics.roadrunner.path.Path
Returns the end pose.
end() - Method in class com.acmerobotics.roadrunner.path.PathSegment
Returns the end pose.
end() - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
Returns the end class MotionState.
end() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
Returns the class MotionState at the end of the segment (time dt).
end() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
 
endDeriv() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
Returns the end heading derivative.
endDeriv() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
Returns the end derivative.
endDeriv() - Method in class com.acmerobotics.roadrunner.path.Path
Returns the end pose derivative.
endDeriv() - Method in class com.acmerobotics.roadrunner.path.PathSegment
Returns the end pose derivative.
endSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
Returns the end heading second derivative.
endSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
Returns the end second derivative.
endSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.Path
Returns the end pose second derivative.
endSecondDeriv() - Method in class com.acmerobotics.roadrunner.path.PathSegment
Returns the end pose second derivative.
endTangentAngle() - Method in class com.acmerobotics.roadrunner.path.PathSegment
Returns the end tangent angle.
endThirdDeriv() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
Returns the end third derivative.
EPSILON - Static variable in class com.acmerobotics.roadrunner.util.MathUtilKt
 
epsilonEquals(other) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
 
epsilonEquals(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 
epsilonEquals($receiver, other) - Static method in class com.acmerobotics.roadrunner.util.MathUtilKt
 
epsilonEqualsHeading(other) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
 
equals(p) - Method in class com.acmerobotics.roadrunner.control.PIDCoefficients
 
equals(p) - Method in class com.acmerobotics.roadrunner.drive.DriveSignal
 
equals(p) - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
 
equals(p) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 
equals(p) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
equals(p) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
equals(p) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
equals(p) - Method in class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
 
equals(p) - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
 
equals(p) - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
 
equals(p) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryMarker
 
equals(p) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
equals(p) - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
 

F

fastProject(queryPoint, projectGuess) - Method in class com.acmerobotics.roadrunner.path.Path
Project queryPoint onto the current path using the iterative method described here.
fieldToRobotAcceleration(fieldPose, fieldVel, fieldAccel) - Static method in class com.acmerobotics.roadrunner.kinematics.Kinematics
Returns the robot pose acceleration corresponding to fieldPose, fieldVel, and fieldAccel.
fieldToRobotVelocity(fieldPose, fieldVel) - Static method in class com.acmerobotics.roadrunner.kinematics.Kinematics
Returns the robot pose velocity corresponding to fieldPose and fieldVel.
flipped() - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
Returns a flipped version of the motion profile.
flipped() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
Returns a flipped (negated) version of the segment.
flipped() - Method in class com.acmerobotics.roadrunner.profile.MotionState
Returns a flipped (negated) version of the state.
floorIndex(query) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
followPath(path) - Method in class com.acmerobotics.roadrunner.followers.GVFFollower
Follow the given path.
followPath(path) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
Follow the given path.
followTrajectory(trajectory) - Method in class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
Follow the given trajectory.
followTrajectory(trajectory) - Method in class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
Follow the given trajectory.
followTrajectory(trajectory) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Follow the given trajectory.
forward(distance) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a line straight forward.
forward(distance) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a line straight forward.
forward(distance, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a line straight forward.
fromClosedInterval(start, endInclusive, count) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression.Companion
 
fromClosedInterval(start, endInclusive, count) - Static method in class com.acmerobotics.roadrunner.util.DoubleProgression
 

G

generateMotionProfile(start, goal, velocityConstraint, accelerationConstraint, 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, velocityConstraint, accelerationConstraint) - 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, maxProfileVel, maxProfileAccel, maxProfileJerk, start, goal, temporalMarkers, displacementMarkers, spatialMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a simple constraint trajectory.
generateSimpleTrajectory(path, maxProfileVel, maxProfileAccel, maxProfileJerk, start, goal, temporalMarkers, displacementMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a simple constraint trajectory.
generateSimpleTrajectory(path, maxProfileVel, maxProfileAccel, maxProfileJerk, start, goal, temporalMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a simple constraint trajectory.
generateSimpleTrajectory(path, maxProfileVel, maxProfileAccel, maxProfileJerk, start, goal) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a simple constraint trajectory.
generateSimpleTrajectory(path, maxProfileVel, maxProfileAccel, maxProfileJerk, start) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a simple constraint trajectory.
generateSimpleTrajectory(path, maxProfileVel, maxProfileAccel, maxProfileJerk) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a simple constraint trajectory.
generateTrajectory(path, velocityConstraint, accelerationConstraint, start, goal, temporalMarkers, displacementMarkers, spatialMarkers, resolution) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a dynamic constraint trajectory.
generateTrajectory(path, velocityConstraint, accelerationConstraint, start, goal, temporalMarkers, displacementMarkers, spatialMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a dynamic constraint trajectory.
generateTrajectory(path, velocityConstraint, accelerationConstraint, start, goal, temporalMarkers, displacementMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a dynamic constraint trajectory.
generateTrajectory(path, velocityConstraint, accelerationConstraint, start, goal, temporalMarkers) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a dynamic constraint trajectory.
generateTrajectory(path, velocityConstraint, accelerationConstraint, start, goal) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a dynamic constraint trajectory.
generateTrajectory(path, velocityConstraint, accelerationConstraint, start) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryGenerator
Generate a dynamic constraint trajectory.
generateTrajectory(path, velocityConstraint, accelerationConstraint) - 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 interface com.acmerobotics.roadrunner.profile.AccelerationConstraint
Returns the maximum profile acceleration at displacement s.
get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
Returns the class MotionState at time t.
get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
Returns the class MotionState at time t.
get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionState
Returns the class MotionState at time t.
get(s) - Method in interface com.acmerobotics.roadrunner.profile.VelocityConstraint
Returns the maximum profile velocity at displacement s.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.AngularVelocityConstraint
Returns the maximum profile velocity.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.MecanumVelocityConstraint
Returns the maximum profile velocity.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.MinAccelerationConstraint
Returns the maximum profile acceleration.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.MinVelocityConstraint
Returns the maximum profile velocity.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.ProfileAccelerationConstraint
Returns the maximum profile acceleration.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.SwerveVelocityConstraint
Returns the maximum profile velocity.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.TankVelocityConstraint
Returns the maximum profile velocity.
get(s, pose, deriv, baseRobotVel) - Method in interface com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraint
Returns the maximum profile acceleration.
get(s, pose, deriv, baseRobotVel) - Method in interface com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint
Returns the maximum profile velocity.
get(s, pose, deriv, baseRobotVel) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.TranslationalVelocityConstraint
Returns the maximum profile velocity.
get(time) - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
 
get(index) - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
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
getAccelConstraint() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
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.DisplacementMarker
 
getCallback() - Method in class com.acmerobotics.roadrunner.trajectory.SpatialMarker
 
getCallback() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
 
getCallback() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryMarker
 
getClock() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
clock
getClock() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
clock
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.Knot
x second derivative
getD2y() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
y second derivative
getDisplacement() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
displacement along the path of
getDriveType() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getDt() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
time delta
getDx() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
x derivative
getDy() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
y derivative
getE() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
 
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).
getExternalHeadingVelocity() - Method in class com.acmerobotics.roadrunner.drive.Drive
The heading velocity used to determine pose velocity in some cases
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
getHeading() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
getHeadingVelocity() - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
Returns the heading of the robot (usually from a gyroscope or IMU).
getInterpolationType() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
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.
getLateralMultiplier() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.Drive
Localizer used to determine the evolution of poseEstimate.
getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
Localizer used to determine the evolution of poseEstimate.
getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
Localizer used to determine the evolution of poseEstimate.
getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.TankDrive
Localizer used to determine the evolution of poseEstimate.
getMarkers() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
 
getMaxAccel() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getMaxAngAccel() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getMaxAngVel() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getMaxVel() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
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
Path being followed if isFollowing is true.
getPath() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
path
getPathBuilder() - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
 
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.
getPoseVelocity() - Method in class com.acmerobotics.roadrunner.drive.Drive
Current robot pose velocity (optional)
getPoseVelocity() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive.MecanumLocalizer
Current robot pose velocity (optional)
getPoseVelocity() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive.SwerveLocalizer
Current robot pose velocity (optional)
getPoseVelocity() - Method in class com.acmerobotics.roadrunner.drive.TankDrive.TankLocalizer
Current robot pose velocity (optional)
getPoseVelocity() - Method in interface com.acmerobotics.roadrunner.localization.Localizer
Current robot pose velocity (optional)
getPoseVelocity() - Method in class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
Current robot pose velocity (optional)
getPoseVelocity() - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
Current robot pose velocity (optional)
getPosition() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
getProducer() - Method in class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
 
getProducer() - Method in class com.acmerobotics.roadrunner.trajectory.TemporalMarker
 
getProfile() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
motion profile
getRawExternalHeading() - Method in class com.acmerobotics.roadrunner.drive.Drive
The raw heading used for computing externalHeading. Not affected by externalHeading setter.
getResolution() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
getRobotLength() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getRobotWidth() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getSegments() - Method in class com.acmerobotics.roadrunner.path.Path
list of path segments
getSize() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
getStart() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
start motion state
getStart() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
getStartPose() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
getStartTangent() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
getStep() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
getTangent() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
getTargetAcceleration() - Method in class com.acmerobotics.roadrunner.control.PIDFController
Target acceleration.
getTargetPosition() - Method in class com.acmerobotics.roadrunner.control.PIDFController
Target position (that is, the controller setpoint).
getTargetVelocity() - Method in class com.acmerobotics.roadrunner.control.PIDFController
Target velocity.
getTime() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryMarker
 
getTrackWidth() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getTrajectory() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Trajectory being followed if isFollowing is true.
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
getVelConstraint() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
getVersion() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
getWaypoints() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
getWheelBase() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
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!)
getWheelVelocities() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
Returns the velocities of the wheels in linear distance units. Positions should exactly match the ordering in setMotorPowers.
getWheelVelocities() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
Returns the velocities of the wheels in linear distance units. Positions should exactly match the ordering in setMotorPowers.
getWheelVelocities() - Method in class com.acmerobotics.roadrunner.drive.TankDrive
Returns the velocities of the wheels in linear distance units. Positions should exactly match the ordering in setMotorPowers.
getWheelVelocities() - Method in class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
Returns the velocities of the tracking wheels in the desired distance units (not encoder counts!)
getWheelVelocities() - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
Returns the velocities 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.Knot
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.Knot
y position
GROUP_FILENAME - Static variable in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
 
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
State-of-the-art path follower based on the class GuidingVectorField.
GVFFollower(maxVel, maxAccel, admissibleError, kN, kOmega, errorMapFunc, clock) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
State-of-the-art path follower based on the class GuidingVectorField.
GVFFollower(maxVel, maxAccel, admissibleError, kN, kOmega, errorMapFunc) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
State-of-the-art path follower based on the class GuidingVectorField.
GVFFollower(maxVel, maxAccel, admissibleError, kN, kOmega) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
State-of-the-art path follower based on the class GuidingVectorField.
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.

H

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.trajectory.config.TrajectoryConfig
 
hashCode() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
hashCode() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
hashCode() - Method in class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
 
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.trajectory.TrajectoryMarker
 
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.
headingVec() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
 
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.

I

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.config.TrajectoryConfigManager
Class containing methods for saving (loading) trajectory configurations to (from) YAML files.
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.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, currentRobotVel) - Method in class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
 
internalUpdate(currentPose) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
 
internalUpdate(currentPose, currentRobotVel) - Method in class com.acmerobotics.roadrunner.followers.RamseteFollower
 
internalUpdate(currentPose, currentRobotVel) - Method in class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
 
internalUpdate(currentPose, currentRobotVel) - 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 is currently executing.
iterator() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
IteratorImpl() - Constructor for class com.acmerobotics.roadrunner.util.DoubleProgression.IteratorImpl
Iterator implementation for class DoubleProgression.

K

kD - Variable in class com.acmerobotics.roadrunner.control.PIDCoefficients
derivative gain
kI - Variable in class com.acmerobotics.roadrunner.control.PIDCoefficients
integral gain
Kinematics - Class in com.acmerobotics.roadrunner.kinematics
A collection of methods for various kinematics-related tasks.
Knot(x, y, dx, dy, d2x, d2y) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
Class for representing the end points of interpolated quintic splines.
Knot(x, y, dx, dy, d2x) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
Class for representing the end points of interpolated quintic splines.
Knot(x, y, dx, dy) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
Class for representing the end points of interpolated quintic splines.
Knot(x, y, dx) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
Class for representing the end points of interpolated quintic splines.
Knot(x, y) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
Class for representing the end points of interpolated quintic splines.
Knot(pos, deriv, secondDeriv) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
 
Knot(pos, deriv) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
 
Knot(pos) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
 
kP - Variable in class com.acmerobotics.roadrunner.control.PIDCoefficients
proportional gain

L

length() - Method in class com.acmerobotics.roadrunner.path.LineSegment
Returns the length of the curve.
length() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
Returns the length of the curve.
length() - Method in class com.acmerobotics.roadrunner.path.Path
Returns the length of the path.
length() - Method in class com.acmerobotics.roadrunner.path.PathSegment
 
length() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
Returns the length of the curve.
LinearInterpolator - Class in com.acmerobotics.roadrunner.path.heading
Linear heading interpolator for time-optimal transitions between poses.
LinearInterpolator(startHeading, angle) - Constructor for class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
Linear heading interpolator for time-optimal transitions between poses.
LineSegment - Class in com.acmerobotics.roadrunner.path
Parametric representation of a line.
LineSegment(start, end) - Constructor for class com.acmerobotics.roadrunner.path.LineSegment
Parametric representation of a line.
lineTo(endPosition) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a line segment with tangent heading interpolation.
lineTo(endPosition) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a line segment with tangent heading interpolation.
lineTo(endPosition, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a line segment with tangent heading interpolation.
lineToConstantHeading(endPosition) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a line segment with constant heading interpolation.
lineToConstantHeading(endPosition) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a line segment with constant heading interpolation.
lineToConstantHeading(endPosition, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a line segment with constant heading interpolation.
lineToLinearHeading(endPose) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a line segment with linear heading interpolation.
lineToLinearHeading(endPose) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a line segment with linear heading interpolation.
lineToLinearHeading(endPose, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a line segment with linear heading interpolation.
lineToSplineHeading(endPose) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a line segment with spline heading interpolation.
lineToSplineHeading(endPose) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a line segment with spline heading interpolation.
lineToSplineHeading(endPose, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a line segment with spline heading interpolation.
load(file) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
Loads a class Trajectory from file.
loadBuilder(file) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
loadConfig(file) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
loadConfig(inputStream) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
loadGroupConfig(dir) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
loadGroupConfig(inputStream) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
Localizer - Interface in com.acmerobotics.roadrunner.localization
Generic interface for estimating robot pose over time.

M

MarkerCallback - Interface in com.acmerobotics.roadrunner.trajectory
 
MarkerCallbackKt - Class in com.acmerobotics.roadrunner.trajectory
 
MathUtil - Class in com.acmerobotics.roadrunner.util
Various math utilities.
MathUtilKt - Class in com.acmerobotics.roadrunner.util
 
MecanumDrive - Class in com.acmerobotics.roadrunner.drive
This class provides the basic functionality of a mecanum drive using class MecanumKinematics.
MecanumDrive(kV, kA, kStatic, trackWidth, wheelBase, lateralMultiplier) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive
This class provides the basic functionality of a mecanum drive using class MecanumKinematics.
MecanumDrive(kV, kA, kStatic, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive
This class provides the basic functionality of a mecanum drive using class MecanumKinematics.
MecanumDrive(kV, kA, kStatic, trackWidth) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive
This class provides the basic functionality of a mecanum drive using class MecanumKinematics.
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.
MecanumVelocityConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Mecanum-specific drive constraints that also limit maximum wheel velocities.
MecanumVelocityConstraint(maxWheelVel, trackWidth, wheelBase, lateralMultiplier) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MecanumVelocityConstraint
Mecanum-specific drive constraints that also limit maximum wheel velocities.
MecanumVelocityConstraint(maxWheelVel, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MecanumVelocityConstraint
Mecanum-specific drive constraints that also limit maximum wheel velocities.
MecanumVelocityConstraint(maxWheelVel, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MecanumVelocityConstraint
Mecanum-specific drive constraints that also limit maximum wheel velocities.
MinAccelerationConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Composite constraint representing the minimum of its constituent acceleration constraints.
MinAccelerationConstraint(constraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MinAccelerationConstraint
Composite constraint representing the minimum of its constituent acceleration constraints.
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
 
MinVelocityConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Composite constraint representing the minimum of its constituent velocity constraints.
MinVelocityConstraint(constraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MinVelocityConstraint
Composite constraint representing the minimum of its constituent velocity 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.

N

NanoClock - Class in com.acmerobotics.roadrunner.util
Clock interface with nanosecond precision and no guarantee about its origin (that is, this is only suited for measuring relative/elapsed time).
NanoClock() - Constructor for class com.acmerobotics.roadrunner.util.NanoClock
Clock interface with nanosecond precision and no guarantee about its origin (that is, this is only suited for measuring relative/elapsed time).
NanoClock.Companion - Class in com.acmerobotics.roadrunner.util
 
next() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression.IteratorImpl
 
norm() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 
norm(angle) - Static method in class com.acmerobotics.roadrunner.util.Angle
Returns angle clamped to [0, 2pi].
normDelta(angleDelta) - Static method in class com.acmerobotics.roadrunner.util.Angle
Returns angleDelta clamped to [-pi, pi].

O

onMarkerReached() - Method in interface com.acmerobotics.roadrunner.trajectory.MarkerCallback
 

P

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 reparameterized 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 reparameterized 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 being followed if isFollowing is true.
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, startTangent) - Constructor for class com.acmerobotics.roadrunner.path.PathBuilder
 
PathBuilder(startPose) - Constructor for class com.acmerobotics.roadrunner.path.PathBuilder
 
PathBuilder(startPose, reversed) - Constructor for class com.acmerobotics.roadrunner.path.PathBuilder
 
PathBuilder(path, s) - Constructor for class com.acmerobotics.roadrunner.path.PathBuilder
 
PathBuilderException - Exception in com.acmerobotics.roadrunner.path
Exception thrown by class PathBuilder.
PathBuilderException() - Constructor for exception com.acmerobotics.roadrunner.path.PathBuilderException
Exception thrown by class PathBuilder.
PathContinuityViolationException - Exception in com.acmerobotics.roadrunner.path
Exception thrown when class PathBuilder methods are chained illegally. This commonly arises when switching from non-tangent interpolation back to tangent interpolation and when splicing paths.
PathContinuityViolationException() - Constructor for exception com.acmerobotics.roadrunner.path.PathContinuityViolationException
Exception thrown when class PathBuilder methods are chained illegally. This commonly arises when switching from non-tangent interpolation back to tangent interpolation and when splicing paths.
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) - 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
Proportional, integral, and derivative (PID) gains used by class PIDFController.
PIDCoefficients(kP, kI, kD) - Constructor for class com.acmerobotics.roadrunner.control.PIDCoefficients
Proportional, integral, and derivative (PID) gains used by class PIDFController.
PIDCoefficients() - Constructor for class com.acmerobotics.roadrunner.control.PIDCoefficients
Proportional, integral, and derivative (PID) gains used by class PIDFController.
PIDFController - Class in com.acmerobotics.roadrunner.control
PID controller with various feedforward components.
PIDFController(pid, kV, kA, kStatic, kF, clock) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
PID controller with various feedforward components.
PIDFController(pid, kV, kA, kStatic, kF) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
PID controller with various feedforward components.
PIDFController(pid, kV, kA, kStatic) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
PID controller with various feedforward components.
PIDFController(pid, kV, kA) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
PID controller with various feedforward components.
PIDFController(pid, kV) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
PID controller with various feedforward components.
PIDFController(pid) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
PID controller with various feedforward components.
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
 
polar(r, theta) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d.Companion
 
polar(r, theta) - Static method in class com.acmerobotics.roadrunner.geometry.Vector2d
 
pos() - Method in class com.acmerobotics.roadrunner.path.QuinticSpline.Knot
 
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
 
produce(length) - Method in interface com.acmerobotics.roadrunner.trajectory.DisplacementProducer
 
produce(duration) - Method in interface com.acmerobotics.roadrunner.trajectory.TimeProducer
 
ProfileAccelerationConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Constraint limiting profile acceleration.
ProfileAccelerationConstraint(maxProfileAccel) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.ProfileAccelerationConstraint
Constraint limiting profile acceleration.
project(queryPoint, ds) - Method in class com.acmerobotics.roadrunner.path.Path
Project queryPoint onto the current path by applying fastProject with various guesses along the path.
projectOnto(other) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 

Q

QuinticPolynomial - Class in com.acmerobotics.roadrunner.path
Quintic polynomial interpolated according to the provided derivatives.
QuinticPolynomial(start, startDeriv, startSecondDeriv, end, endDeriv, endSecondDeriv) - Constructor for class com.acmerobotics.roadrunner.path.QuinticPolynomial
Quintic polynomial interpolated according to the provided derivatives.
QuinticPolynomialKt - Class in com.acmerobotics.roadrunner.path
 
QuinticSpline - Class in com.acmerobotics.roadrunner.path
Combination of two quintic polynomials into a 2D quintic spline. See this short paper for some motivation and implementation details.
QuinticSpline(start, end, maxDeltaK, maxSegmentLength, maxDepth) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSpline
Combination of two quintic polynomials into a 2D quintic spline. See this short paper for some motivation and implementation details.
QuinticSpline.Knot - Class in com.acmerobotics.roadrunner.path
Class for representing the end points of interpolated quintic splines.

R

RamseteFollower - Class in com.acmerobotics.roadrunner.followers
Time-varying, non-linear feedback controller for nonholonomic drives. See equation 5.12 of Ramsete01.pdf.
RamseteFollower(b, zeta, admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.RamseteFollower
Time-varying, non-linear feedback controller for nonholonomic drives. See equation 5.12 of Ramsete01.pdf.
RamseteFollower(b, zeta, admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.RamseteFollower
Time-varying, non-linear feedback controller for nonholonomic drives. See equation 5.12 of Ramsete01.pdf.
RamseteFollower(b, zeta, admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.RamseteFollower
Time-varying, non-linear feedback controller for nonholonomic drives. See equation 5.12 of Ramsete01.pdf.
RamseteFollower(b, zeta) - Constructor for class com.acmerobotics.roadrunner.followers.RamseteFollower
Time-varying, non-linear feedback controller for nonholonomic drives. See equation 5.12 of Ramsete01.pdf.
relativeOdometryUpdate(fieldPose, robotPoseDelta) - Static method in class com.acmerobotics.roadrunner.kinematics.Kinematics
Performs a relative odometry update. Note: this assumes that the robot moves with constant velocity over the measurement interval.
reparam(s) - Method in class com.acmerobotics.roadrunner.path.PathSegment
 
reparam$module(s) - Method in class com.acmerobotics.roadrunner.path.LineSegment
 
reparam$module(s) - Method in class com.acmerobotics.roadrunner.path.QuinticSpline
 
reset() - Method in class com.acmerobotics.roadrunner.control.PIDFController
Reset the controller's integral sum.
reversed() - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
Returns a reversed version of the motion profile.
reversed() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
Returns a reversed version of the segment. Note: it isn't possible to reverse a segment completely so this method only guarantees that the start and end velocities will be swapped.
robotToModuleAccelerationVectors(robotAccel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the acceleration vectors corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToModuleAccelerationVectors(robotAccel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the acceleration vectors corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToModuleAngularVelocities(robotVel, robotAccel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the module angular velocities corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToModuleAngularVelocities(robotVel, robotAccel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the module angular velocities corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToModuleOrientations(robotVel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the module orientations (in radians) corresponding to robotVel given the provided trackWidth and wheelBase.
robotToModuleOrientations(robotVel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the module orientations (in radians) corresponding to robotVel given the provided trackWidth and wheelBase.
robotToModuleVelocityVectors(robotVel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the wheel velocity vectors corresponding to robotVel given the provided trackWidth and wheelBase.
robotToModuleVelocityVectors(robotVel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the wheel velocity vectors corresponding to robotVel given the provided trackWidth and wheelBase.
robotToWheelAccelerations(robotAccel, trackWidth, wheelBase, lateralMultiplier) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the wheel accelerations corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToWheelAccelerations(robotAccel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the wheel accelerations corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToWheelAccelerations(robotAccel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the wheel accelerations corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToWheelAccelerations(robotVel, robotAccel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the wheel accelerations corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToWheelAccelerations(robotVel, robotAccel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the wheel accelerations corresponding to robotAccel given the provided trackWidth and wheelBase.
robotToWheelAccelerations(robotAccel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.TankKinematics
Computes the wheel accelerations corresponding to robotAccel given trackWidth.
robotToWheelVelocities(robotVel, trackWidth, wheelBase, lateralMultiplier) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the wheel velocities corresponding to robotVel given the provided trackWidth and wheelBase.
robotToWheelVelocities(robotVel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the wheel velocities corresponding to robotVel given the provided trackWidth and wheelBase.
robotToWheelVelocities(robotVel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the wheel velocities corresponding to robotVel given the provided trackWidth and wheelBase.
robotToWheelVelocities(robotVel, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the wheel velocities corresponding to robotVel given the provided trackWidth and wheelBase.
robotToWheelVelocities(robotVel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the wheel velocities corresponding to robotVel given the provided trackWidth and wheelBase.
robotToWheelVelocities(robotVel, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.TankKinematics
Computes the wheel velocities corresponding to robotVel given trackWidth.
rotated(angle) - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 

S

saveConfig(trajectoryConfig, file) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
saveGroupConfig(trajectoryConfig, dir) - Static method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfigManager
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.Knot
 
seconds() - Method in class com.acmerobotics.roadrunner.util.NanoClock
Returns the number of seconds since an arbitrary (yet consistent) origin.
segment(s) - Method in class com.acmerobotics.roadrunner.path.Path
 
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
Localizer used to determine the evolution of poseEstimate.
setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
Localizer used to determine the evolution of poseEstimate.
setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
Localizer used to determine the evolution of poseEstimate.
setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
Localizer used to determine the evolution of poseEstimate.
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
Path being followed if isFollowing is true.
setPathBuilder(p) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
 
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.
setPoseVelocity(p) - Method in class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
Current robot pose velocity (optional)
setPoseVelocity(p) - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
Current robot pose velocity (optional)
setTargetAcceleration(p) - Method in class com.acmerobotics.roadrunner.control.PIDFController
Target acceleration.
setTargetPosition(p) - Method in class com.acmerobotics.roadrunner.control.PIDFController
Target position (that is, the controller setpoint).
setTargetVelocity(p) - Method in class com.acmerobotics.roadrunner.control.PIDFController
Target velocity.
setTrajectory(p) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Trajectory being followed if isFollowing is true.
SimpleTrajectoryBuilder - Class in com.acmerobotics.roadrunner.trajectory
Builder for trajectories with static constraints.
SimpleTrajectoryBuilder(startPose, startTangent, maxProfileVel, maxProfileAccel, maxProfileJerk) - 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, startTangent, maxProfileVel, maxProfileAccel) - 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, maxProfileVel, maxProfileAccel) - 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, reversed, maxProfileVel, maxProfileAccel, maxProfileJerk) - Constructor for class com.acmerobotics.roadrunner.trajectory.SimpleTrajectoryBuilder
 
SimpleTrajectoryBuilder(trajectory, t, maxProfileVel, maxProfileAccel, maxProfileJerk) - 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
 
size() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
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, startHeadingDeriv, startHeadingSecondDeriv, endHeadingDeriv, endHeadingSecondDeriv) - 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).
SplineInterpolator(startHeading, endHeading, startHeadingDeriv, startHeadingSecondDeriv, endHeadingDeriv) - 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).
SplineInterpolator(startHeading, endHeading, startHeadingDeriv, startHeadingSecondDeriv) - 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).
SplineInterpolator(startHeading, endHeading, startHeadingDeriv) - 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).
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(endPosition, endTangent) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a spline segment with tangent heading interpolation.
splineTo(endPosition, endTangent) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a spline segment with tangent heading interpolation.
splineTo(endPosition, endTangent, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a spline segment with tangent heading interpolation.
splineToConstantHeading(endPosition, endTangent) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a spline segment with constant heading interpolation.
splineToConstantHeading(endPosition, endTangent) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a spline segment with constant heading interpolation.
splineToConstantHeading(endPosition, endTangent, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a spline segment with constant heading interpolation.
splineToLinearHeading(endPose, endTangent) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a spline segment with linear heading interpolation.
splineToLinearHeading(endPose, endTangent) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a spline segment with linear heading interpolation.
splineToLinearHeading(endPose, endTangent, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a spline segment with linear heading interpolation.
splineToSplineHeading(endPose, endTangent) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a spline segment with spline heading interpolation.
splineToSplineHeading(endPose, endTangent) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a spline segment with spline heading interpolation.
splineToSplineHeading(endPose, endTangent, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a spline segment with spline heading interpolation.
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
Returns the start class MotionState.
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.
startTangentAngle() - Method in class com.acmerobotics.roadrunner.path.PathSegment
Returns the start tangent angle.
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.
strafeLeft(distance, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
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.
strafeRight(distance, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a segment that strafes right in the robot reference frame.
strafeTo(endPosition) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
Adds a strafe segment (i.e., a line segment with constant heading interpolation).
strafeTo(endPosition) - Method in class com.acmerobotics.roadrunner.trajectory.BaseTrajectoryBuilder
Adds a strafe path segment.
strafeTo(endPosition, velConstraintOverride, accelConstraintOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
Adds a strafe path segment.
SwerveDrive - Class in com.acmerobotics.roadrunner.drive
This class provides the basic functionality of a swerve drive using class SwerveKinematics.
SwerveDrive(kV, kA, kStatic, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive
This class provides the basic functionality of a swerve drive using class SwerveKinematics.
SwerveDrive(kV, kA, kStatic, trackWidth) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive
This class provides the basic functionality of a swerve drive using class SwerveKinematics.
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.
SwerveVelocityConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Mecanum-specific drive constraints that also limit maximum wheel velocities.
SwerveVelocityConstraint(maxWheelVel, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.SwerveVelocityConstraint
Mecanum-specific drive constraints that also limit maximum wheel velocities.
SwerveVelocityConstraint(maxWheelVel, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.SwerveVelocityConstraint
Mecanum-specific drive constraints that also limit maximum wheel velocities.
system() - Method in class com.acmerobotics.roadrunner.util.NanoClock.Companion
Returns a class NanoClock backed by System.nanoTime.
system() - Static method in class com.acmerobotics.roadrunner.util.NanoClock
Returns a class NanoClock backed by System.nanoTime.

T

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.
tangentAngle(s, t) - Method in class com.acmerobotics.roadrunner.path.PathSegment
 
tangentAngle(s) - Method in class com.acmerobotics.roadrunner.path.PathSegment
 
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(offset) - Constructor for class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
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.
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.
TankVelocityConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Tank-specific drive constraints that also limit maximum wheel velocities.
TankVelocityConstraint(maxWheelVel, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.TankVelocityConstraint
Tank-specific drive constraints that also limit maximum wheel velocities.
TemporalMarker - Class in com.acmerobotics.roadrunner.trajectory
Trajectory marker that is triggered when the specified time passes.
TemporalMarker(producer, 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(wheelPoses) - Constructor for class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
Localizer based on three unpowered tracking omni wheels.
TimeProducer - Interface in com.acmerobotics.roadrunner.trajectory
 
TimeProducerKt - Class in com.acmerobotics.roadrunner.trajectory
 
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.trajectory.config.TrajectoryConfig
 
toString() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
 
toString() - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
 
toString() - Method in class com.acmerobotics.roadrunner.trajectory.DisplacementMarker
 
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.trajectory.TrajectoryMarker
 
toString() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
toString() - Method in class com.acmerobotics.roadrunner.util.GuidingVectorField.GVFResult
 
toTrajectory(groupConfig) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
toTrajectoryBuilder(groupConfig) - Method in class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
 
trajectory - Variable in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Trajectory being followed if isFollowing is true.
Trajectory - Class in com.acmerobotics.roadrunner.trajectory
Trajectory backed by a class Path and a class MotionProfile.
Trajectory(path, profile, markers) - Constructor for class com.acmerobotics.roadrunner.trajectory.Trajectory
Trajectory backed by a class Path and a class MotionProfile.
Trajectory(path, profile) - Constructor for class com.acmerobotics.roadrunner.trajectory.Trajectory
Trajectory backed by a class Path and a class MotionProfile.
TrajectoryAccelerationConstraint - Interface in com.acmerobotics.roadrunner.trajectory.constraints
 
TrajectoryAccelerationConstraintKt - Class in com.acmerobotics.roadrunner.trajectory.constraints
 
TrajectoryBuilder - Class in com.acmerobotics.roadrunner.trajectory
Builder for trajectories with dynamic constraints.
TrajectoryBuilder(startPose, startTangent, baseVelConstraint, baseAccelConstraint, 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, startTangent, baseVelConstraint, baseAccelConstraint) - 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, baseVelConstraint, baseAccelConstraint) - 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, reversed, baseVelConstraint, baseAccelConstraint, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
 
TrajectoryBuilder(startPose, reversed, baseVelConstraint, baseAccelConstraint) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
 
TrajectoryBuilder(trajectory, t, baseVelConstraint, baseAccelConstraint, 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, baseVelConstraint, baseAccelConstraint) - 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.config
Configuration describing a basic trajectory (a simpler frontend alternative to class BaseTrajectoryBuilder).
TrajectoryConfig(startPose, startTangent, waypoints, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig
Configuration describing a basic trajectory (a simpler frontend alternative to class BaseTrajectoryBuilder).
TrajectoryConfig.HeadingInterpolationType - Enum in com.acmerobotics.roadrunner.trajectory.config
Heading interpolation for a specific trajectory configuration step.
TrajectoryConfig.Waypoint - Class in com.acmerobotics.roadrunner.trajectory.config
Description of a single segment of a composite trajectory.
TrajectoryConfigManager - Class in com.acmerobotics.roadrunner.trajectory.config
Class containing methods for saving (loading) trajectory configurations to (from) YAML files.
TrajectoryFollower - Class in com.acmerobotics.roadrunner.followers
Generic class Trajectory follower for time-based pose reference tracking.
TrajectoryFollower(admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Generic class Trajectory follower for time-based pose reference tracking.
TrajectoryFollower(admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Generic class Trajectory follower for time-based pose reference tracking.
TrajectoryFollower(admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Generic class Trajectory follower for time-based pose reference tracking.
TrajectoryFollower() - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Generic class Trajectory follower for time-based pose reference tracking.
TrajectoryGenerator - Class in com.acmerobotics.roadrunner.trajectory
Trajectory generator for creating trajectories with dynamic and static constraints from paths.
TrajectoryGroupConfig - Class in com.acmerobotics.roadrunner.trajectory.config
Configuration describing constraints and other robot-specific parameters that are shared by a group of trajectories.
TrajectoryGroupConfig(maxVel, maxAccel, maxAngVel, maxAngAccel, robotLength, robotWidth, driveType, trackWidth, wheelBase, lateralMultiplier) - Constructor for class com.acmerobotics.roadrunner.trajectory.config.TrajectoryGroupConfig
Configuration describing constraints and other robot-specific parameters that are shared by a group of trajectories.
TrajectoryGroupConfig.DriveType - Enum in com.acmerobotics.roadrunner.trajectory.config
Type of drivetrain.
TrajectoryMarker - Class in com.acmerobotics.roadrunner.trajectory
Trajectory marker that is triggered when the specified time passes.
TrajectoryMarker(time, callback) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryMarker
Trajectory marker that is triggered when the specified time passes.
TrajectoryVelocityConstraint - Interface in com.acmerobotics.roadrunner.trajectory.constraints
 
TrajectoryVelocityConstraintKt - Class in com.acmerobotics.roadrunner.trajectory.constraints
 
TranslationalVelocityConstraint - Class in com.acmerobotics.roadrunner.trajectory.constraints
Constraint limiting translational velocity.
TranslationalVelocityConstraint(maxTranslationalVel) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.TranslationalVelocityConstraint
Constraint limiting translational velocity.
TwoTrackingWheelLocalizer - Class in com.acmerobotics.roadrunner.localization
Localizer based on two unpowered tracking omni wheels and an orientation sensor.
TwoTrackingWheelLocalizer(wheelPoses) - Constructor for class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
Localizer based on two unpowered tracking omni wheels and an orientation sensor.

U

unaryMinus() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
 
unaryMinus() - Method in class com.acmerobotics.roadrunner.geometry.Vector2d
 
unaryMinus() - Method in class com.acmerobotics.roadrunner.util.DoubleProgression
 
UnsatisfiableConstraint - Exception in com.acmerobotics.roadrunner.trajectory.constraints
Exception thrown when no velocity or acceleration combination exists that satisfies the constraint.
UnsatisfiableConstraint() - Constructor for exception com.acmerobotics.roadrunner.trajectory.constraints.UnsatisfiableConstraint
Exception thrown when no velocity or acceleration combination exists that satisfies the constraint.
update(measuredPosition, measuredVelocity) - Method in class com.acmerobotics.roadrunner.control.PIDFController
Run a single iteration of the controller.
update(measuredPosition) - Method in class com.acmerobotics.roadrunner.control.PIDFController
Run a single iteration of the controller.
update() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive.MecanumLocalizer
Completes a single localization update.
update() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive.SwerveLocalizer
Completes a single localization update.
update() - Method in class com.acmerobotics.roadrunner.drive.TankDrive.TankLocalizer
Completes a single localization update.
update(currentPose) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
Run a single iteration of the path follower.
update(currentPose, currentRobotVel) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Run a single iteration of the trajectory follower.
update(currentPose) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
Run a single iteration of the trajectory follower.
update() - Method in interface com.acmerobotics.roadrunner.localization.Localizer
Completes a single localization update.
update() - Method in class com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer
Completes a single localization update.
update() - Method in class com.acmerobotics.roadrunner.localization.TwoTrackingWheelLocalizer
Completes a single localization update.
updatePoseEstimate() - Method in class com.acmerobotics.roadrunner.drive.Drive
Updates poseEstimate with the most recent positional change.

V

vec() - Method in class com.acmerobotics.roadrunner.geometry.Pose2d
 
Vector2d - Class in com.acmerobotics.roadrunner.geometry
Class for representing 2D vectors (x and y).
Vector2d(x, y) - Constructor for class com.acmerobotics.roadrunner.geometry.Vector2d
Class for representing 2D vectors (x and y).
Vector2d(x) - Constructor for class com.acmerobotics.roadrunner.geometry.Vector2d
Class for representing 2D vectors (x and y).
Vector2d() - Constructor for class com.acmerobotics.roadrunner.geometry.Vector2d
Class for representing 2D vectors (x and y).
Vector2d.Companion - Class in com.acmerobotics.roadrunner.geometry
 
Vector2dKt - Class in com.acmerobotics.roadrunner.geometry
 
velocity(time) - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
 
VelocityConstraint - Interface in com.acmerobotics.roadrunner.profile
 
VelocityConstraintKt - Class in com.acmerobotics.roadrunner.profile
 

W

Waypoint(position, heading, tangent, interpolationType) - Constructor for class com.acmerobotics.roadrunner.trajectory.config.TrajectoryConfig.Waypoint
Description of a single segment of a composite trajectory.
wheelToRobotVelocities(wheelVelocities, trackWidth, wheelBase, lateralMultiplier) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the robot velocity corresponding to wheelVelocities and the given drive parameters.
wheelToRobotVelocities(wheelVelocities, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the robot velocity corresponding to wheelVelocities and the given drive parameters.
wheelToRobotVelocities(wheelVelocities, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.MecanumKinematics
Computes the robot velocity corresponding to wheelVelocities and the given drive parameters.
wheelToRobotVelocities(wheelVelocities, moduleOrientations, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the robot velocities corresponding to wheelVelocities, moduleOrientations, and the drive parameters.
wheelToRobotVelocities(wheelVelocities, moduleOrientations, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.SwerveKinematics
Computes the robot velocities corresponding to wheelVelocities, moduleOrientations, and the drive parameters.
wheelToRobotVelocities(wheelVelocities, trackWidth) - Static method in class com.acmerobotics.roadrunner.kinematics.TankKinematics
Computes the robot velocity corresponding to wheelVelocities and the given drive parameters.
WiggleInterpolator - Class in com.acmerobotics.roadrunner.path.heading
Heading interpolator that wraps another interpolator and adds sinusoidal oscillations ("wiggles") while preserving continuity. More specifically, the wiggle function is composed of a sine wave with a quintic spline on either end.
WiggleInterpolator(amplitude, desiredPeriod, baseInterpolator) - Constructor for class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
Heading interpolator that wraps another interpolator and adds sinusoidal oscillations ("wiggles") while preserving continuity. More specifically, the wiggle function is composed of a sine wave with a quintic spline on either end.
WiggleInterpolatorKt - Class in com.acmerobotics.roadrunner.path.heading
 
< A B C D E F G H I K L M N O P Q R S T U V W 
Skip navigation links