- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
Returns the heading derivative at the specified displacement.
- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading derivative at the specified displacement.
- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
-
Returns the heading derivative at the specified displacement.
- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Returns the heading derivative at the specified displacement.
- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
Returns the heading derivative at the specified displacement.
- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
Returns the heading derivative at the specified displacement.
- deriv(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreePolynomial
-
Returns the derivative of the polynomial at t.
- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the derivative displacement units along the curve.
- deriv(displacement) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose derivative displacement units along the path.
- 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.QuinticSplineSegment.Waypoint
-
- displacementToParameter$module(displacement) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- displacementToParameter$module(displacement) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- displacementToParameter$module(displacement) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- distanceTo(other) - Method in class com.acmerobotics.roadrunner.Vector2d
-
- div(scalar) - Method in class com.acmerobotics.roadrunner.Pose2d
-
- div($receiver, pose) - Static method in class com.acmerobotics.roadrunner.Pose2dKt
-
- div(scalar) - Method in class com.acmerobotics.roadrunner.Vector2d
-
- div($receiver, vector) - Static method in class com.acmerobotics.roadrunner.Vector2dKt
-
- dot(other) - Method in class com.acmerobotics.roadrunner.Vector2d
-
- Drive - Class in com.acmerobotics.roadrunner.drive
-
Abstraction for generic robot drive motion and localization. Robot poses are specified in a coordinate system with
positive x pointing forward, positive y pointing left, and positive heading measured counter-clockwise from the
x-axis.
- Drive() - Constructor for class com.acmerobotics.roadrunner.drive.Drive
-
Abstraction for generic robot drive motion and localization. Robot poses are specified in a coordinate system with
positive x pointing forward, positive y pointing left, and positive heading measured counter-clockwise from the
x-axis.
- DriveConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
This class describes general robot trajectory constraints. More specifically, for paths, the robot velocity,
robot acceleration, and robot angular velocity are limited. For point turns, the angular velocity and angular
acceleration are limited.
- DriveConstraints(maximumVelocity, maximumAcceleration, maximumAngularVelocity, maximumAngularAcceleration) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
This class describes general robot trajectory constraints. More specifically, for paths, the robot velocity,
robot acceleration, and robot angular velocity are limited. For point turns, the angular velocity and angular
acceleration are limited.
- duration() - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
-
Returns the duration of the motion profile.
- duration() - Method in class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
Returns the duration of the segment.
- duration() - Method in class com.acmerobotics.roadrunner.trajectory.PointTurn
-
Returns the duration of the segment.
- duration() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
Returns the trajectory duration.
- duration() - Method in interface com.acmerobotics.roadrunner.trajectory.TrajectorySegment
-
Returns the duration of the segment.
- duration() - Method in class com.acmerobotics.roadrunner.trajectory.WaitSegment
-
Returns the duration of the segment.
- generateMotionProfile(start, goal, constraints, resolution) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a motion profile with dynamic maximum velocity and acceleration. Uses the algorithm described in
section 3.2 of
Sprunk2008.pdf. Warning:
Profiles may be generated incorrectly if the endpoint velocity/acceleration values preclude the obedience of the
motion constraints. To protect against this, verify the continuity of the generated profile or keep the start and
goal velocities at 0.
- generateMotionProfile(start, goal, constraints) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a motion profile with dynamic maximum velocity and acceleration. Uses the algorithm described in
section 3.2 of
Sprunk2008.pdf. Warning:
Profiles may be generated incorrectly if the endpoint velocity/acceleration values preclude the obedience of the
motion constraints. To protect against this, verify the continuity of the generated profile or keep the start and
goal velocities at 0.
- generateSimpleMotionProfile(start, goal, maximumVelocity, maximumAcceleration, maximumJerk, overshoot) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a simple motion profile with constant maximumVelocity, maximumAcceleration, and maximumJerk. 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
satisfiable.
- generateSimpleMotionProfile(start, goal, maximumVelocity, maximumAcceleration, maximumJerk) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a simple motion profile with constant maximumVelocity, maximumAcceleration, and maximumJerk. 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
satisfiable.
- generateSimpleMotionProfile(start, goal, maximumVelocity, maximumAcceleration) - Static method in class com.acmerobotics.roadrunner.profile.MotionProfileGenerator
-
Generates a simple motion profile with constant maximumVelocity, maximumAcceleration, and maximumJerk. 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
satisfiable.
- get(x, y) - Method in class com.acmerobotics.roadrunner.followers.GuidingVectorField
-
Returns the normalized value of the vector field at the given point.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
Returns the heading at the specified displacement.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading at the specified displacement.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
-
Returns the heading at the specified displacement.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Returns the heading at the specified displacement.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
Returns the heading at the specified displacement.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
Returns the heading at the specified displacement.
- get(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreePolynomial
-
Returns the value of the polynomial at t.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the vector displacement units along the curve.
- get(displacement) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose displacement units along the path.
- get(t) - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
Returns the value of the polynomial at t.
- get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
-
- get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
-
- get(t) - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- get(time) - Method in class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
Returns the pose at the given time.
- get(time) - Method in class com.acmerobotics.roadrunner.trajectory.PointTurn
-
Returns the pose at the given time.
- get(time) - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
Returns the pose at the specified time.
- get(time) - Method in interface com.acmerobotics.roadrunner.trajectory.TrajectorySegment
-
Returns the pose at the given time.
- get(time) - Method in class com.acmerobotics.roadrunner.trajectory.WaitSegment
-
Returns the pose at the given time.
- getA() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getA() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getB() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getC() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getClock() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
clock
- getClock() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
clock
- getConstraints() - Method in class com.acmerobotics.roadrunner.trajectory.PointTurn
-
drive constraints
- getConstraints() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
constraints
- getD() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getD2x() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
x second derivative
- getD2y() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
y second derivative
- getDisplacement() - Method in class com.acmerobotics.roadrunner.followers.GuidingVectorField.GVFResult
-
displacement along the path of
- getDisplacement() - Method in class com.acmerobotics.roadrunner.path.Path.ProjectionResult
-
displacement along the path
- getDistance() - Method in class com.acmerobotics.roadrunner.path.Path.ProjectionResult
-
Euclidean distance between the path and query points
- getDt() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
-
time delta
- getDx() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
x derivative
- getDy() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
y derivative
- getE() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getError() - Method in class com.acmerobotics.roadrunner.followers.GuidingVectorField.GVFResult
-
signed cross track error
- getExtended(x, y, projectGuess) - Method in class com.acmerobotics.roadrunner.followers.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.MecanumDrive
-
Returns the robot's heading in radians as measured by an external sensor (e.g., IMU, gyroscope). Heading is
measured counter-clockwise from the x-axis.
- getExternalHeading() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Returns the robot's heading in radians as measured by an external sensor (e.g., IMU, gyroscope). Heading is
measured counter-clockwise from the x-axis.
- getExternalHeading() - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
Returns the robot's heading in radians as measured by an external sensor (e.g., IMU, gyroscope). Heading is
measured counter-clockwise from the x-axis.
- getF() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- getHeading() - Method in class com.acmerobotics.roadrunner.drive.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.Pose2d
-
- getInterpolated(key) - Method in class com.acmerobotics.roadrunner.util.InterpolatingTreeMap
-
Returns the linearly-interpolated value for key or null if it's out of range.
- getInterpolators() - Method in class com.acmerobotics.roadrunner.path.Path
-
heading interpolators
- getJ() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getLastError() - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.GVFFollower
-
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.RamseteFollower
-
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
- getLastError() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.Drive
-
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- getLocalizer() - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
- getModuleOrientations() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- getParametricCurve() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Base parametric curve
- getParametricCurves() - Method in class com.acmerobotics.roadrunner.path.Path
-
parametric curves
- getPath() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
- getPathPoint() - Method in class com.acmerobotics.roadrunner.followers.GuidingVectorField.GVFResult
-
point on the path from the projection
- getPaths() - Method in class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
paths
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.drive.Drive
-
The robot's current pose estimate.
- getPoseEstimate() - Method in interface com.acmerobotics.roadrunner.drive.Localizer
-
Current robot 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 class com.acmerobotics.roadrunner.drive.ThreeTrackingWheelLocalizer
-
Current robot pose estimate.
- getPoseEstimate() - Method in class com.acmerobotics.roadrunner.drive.TwoTrackingWheelLocalizer
-
Current robot pose estimate.
- getPoses() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
poses
- getProfile() - Method in class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
Motion profile used for time parametrization of the paths.
- getProfile() - Method in class com.acmerobotics.roadrunner.trajectory.PointTurn
-
Motion profile for the time parametrization of the turn.
- getResolution() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
resolution used for path-based segments
- getReversed() - Method in class com.acmerobotics.roadrunner.path.Path
-
whether or not to travel along the path segment in reverse
- getSegments() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
trajectory segments
- getStart() - Method in class com.acmerobotics.roadrunner.profile.MotionSegment
-
start motion state
- getStart() - Method in class com.acmerobotics.roadrunner.trajectory.PointTurn
-
start pose
- getTargetPosition() - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Target position (that is, the controller setpoint).
- getTrackWidth() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
lateral distance between pairs of wheels on different sides of the robot
- getTrackWidth() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
lateral distance between pairs of wheels on different sides of the robot
- getTrackWidth() - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
lateral distance between pairs of wheels on different sides of the robot
- getTrackWidth() - Method in class com.acmerobotics.roadrunner.trajectory.constraints.TankConstraints
-
track width
- getTrajectory() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- getTrajectoryConstraintsList() - Method in class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
motion constraints for each respective path
- getV() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getVector() - Method in class com.acmerobotics.roadrunner.followers.GuidingVectorField.GVFResult
-
normalized direction vector of the GVF
- getWheelBase() - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
distance between pairs of wheels on the same side of the robot
- getWheelBase() - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
distance between pairs of wheels on the same side of the robot
- 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
MecanumDrive.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
SwerveDrive.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
TankDrive.setMotorPowers
.
- getWheelPositions() - Method in class com.acmerobotics.roadrunner.drive.ThreeTrackingWheelLocalizer
-
Returns the positions of the tracking wheels in the desired distance units (not encoder counts!)
- getWheelPositions() - Method in class com.acmerobotics.roadrunner.drive.TwoTrackingWheelLocalizer
-
Returns the positions of the tracking wheels in the desired distance units (not encoder counts!)
- getX() - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- getX() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
X polynomial (i.e., x(t))
- getX() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
x position
- getX() - Method in class com.acmerobotics.roadrunner.Pose2d
-
- getX() - Method in class com.acmerobotics.roadrunner.profile.MotionState
-
- getX() - Method in class com.acmerobotics.roadrunner.Vector2d
-
- getY() - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- getY() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
Y polynomial (i.e., y(t))
- getY() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
y position
- getY() - Method in class com.acmerobotics.roadrunner.Pose2d
-
- getY() - Method in class com.acmerobotics.roadrunner.Vector2d
-
- GuidingVectorField - Class in com.acmerobotics.roadrunner.followers
-
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.followers.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.followers
-
Container for the direction of the GVF and intermediate values used in its computation.
- GVFFollower - Class in com.acmerobotics.roadrunner.followers
-
- GVFFollower(drive, constraints, admissibleError, kN, kOmega, kV, kA, kStatic, errorMapFunc, clock) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
-
- GVFFollower(drive, constraints, admissibleError, kN, kOmega, kV, kA, kStatic, errorMapFunc) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
-
- GVFFollower(drive, constraints, admissibleError, kN, kOmega, kV, kA, kStatic) - Constructor for class com.acmerobotics.roadrunner.followers.GVFFollower
-
- GVFResult(vector, pathPoint, displacement, error) - Constructor for class com.acmerobotics.roadrunner.followers.GuidingVectorField.GVFResult
-
Container for the direction of the GVF and intermediate values used in its computation.
- init(parametricCurve) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Initialize the interpolator with a parametricCurve.
- init(parametricCurve) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Initialize the interpolator with a parametricCurve.
- init(parametricCurve) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
Initialize the interpolator with a parametricCurve.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.drive.Kinematics
-
A collection of methods for various kinematics-related tasks.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.drive.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.drive.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.drive.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.TrajectoryLoader
-
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.util.Angle
-
Various utilities for working with angles.
- INSTANCE - Static variable in class com.acmerobotics.roadrunner.util.MathUtil
-
Various math utilities.
- internalDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- internalDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- internalGet$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalGet$module(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- internalGet$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- internalSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- internalSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- internalThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- internalThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- internalThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- InterpolatingTreeMap - Class in com.acmerobotics.roadrunner.util
-
Interpolating Tree Maps are used to get values at points that are not defined by making a guess from points that are
defined. This uses linear interpolation.
- InterpolatingTreeMap() - Constructor for class com.acmerobotics.roadrunner.util.InterpolatingTreeMap
-
Interpolating Tree Maps are used to get values at points that are not defined by making a guess from points that are
defined. This uses linear interpolation.
- isFollowing() - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
Returns true if the current path has finished executing.
- isFollowing() - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
Returns true if the current trajectory has finished executing.
- MathUtil - Class in com.acmerobotics.roadrunner.util
-
Various math utilities.
- maximumAcceleration(displacement) - Method in interface com.acmerobotics.roadrunner.profile.MotionConstraints
-
Returns the maximum acceleration displacement units along the profile.
- maximumAcceleration - Variable in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
constant maximum acceleration
- maximumAcceleration(displacement) - Method in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
Returns the maximum acceleration displacement units along the profile.
- maximumAcceleration - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum robot acceleration
- maximumAcceleration(pose, poseDeriv, poseSecondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
Returns the maximum acceleration for the given pose derivatives.
- maximumAcceleration(pose, poseDeriv, poseSecondDeriv) - Method in interface com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryConstraints
-
Returns the maximum acceleration for the given pose derivatives.
- maximumAngularAcceleration - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum angular acceleration
- maximumAngularVelocity - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum angular velocity
- maximumVelocity(displacement) - Method in interface com.acmerobotics.roadrunner.profile.MotionConstraints
-
Returns the maximum velocity displacement units along the profile.
- maximumVelocity - Variable in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
constant maximum velocity
- maximumVelocity(displacement) - Method in class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
Returns the maximum velocity displacement units along the profile.
- maximumVelocity - Variable in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
maximum robot velocity
- maximumVelocity(pose, poseDeriv, poseSecondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints
-
Returns the maximum velocity for the given pose derivatives.
- maximumVelocity(pose, poseDeriv, poseSecondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.MecanumConstraints
-
Returns the maximum velocity for the given pose derivatives.
- maximumVelocity(pose, poseDeriv, poseSecondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.SwerveConstraints
-
Returns the maximum velocity for the given pose derivatives.
- maximumVelocity(pose, poseDeriv, poseSecondDeriv) - Method in class com.acmerobotics.roadrunner.trajectory.constraints.TankConstraints
-
Returns the maximum velocity for the given pose derivatives.
- maximumVelocity(pose, poseDeriv, poseSecondDeriv) - Method in interface com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryConstraints
-
Returns the maximum velocity for the given pose derivatives.
- MecanumConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- MecanumConstraints(baseConstraints, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MecanumConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- MecanumConstraints(baseConstraints, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.MecanumConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- MecanumDrive - Class in com.acmerobotics.roadrunner.drive
-
- MecanumDrive(trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- MecanumDrive(trackWidth) - Constructor for class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- MecanumDrive.MecanumLocalizer - Class in com.acmerobotics.roadrunner.drive
-
Default localizer for mecanum drives based on the drive encoders and (optionally) a heading sensor.
- MecanumKinematics - Class in com.acmerobotics.roadrunner.drive
-
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.
- MecanumPIDVAFollower - 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.
- MecanumPIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic, admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.MecanumPIDVAFollower
-
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.
- MecanumPIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic, admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.MecanumPIDVAFollower
-
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.
- MecanumPIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic, admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.MecanumPIDVAFollower
-
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.
- MecanumPIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic) - Constructor for class com.acmerobotics.roadrunner.followers.MecanumPIDVAFollower
-
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.
- minus(other) - Method in class com.acmerobotics.roadrunner.Pose2d
-
- minus(other) - Method in class com.acmerobotics.roadrunner.Vector2d
-
- MotionConstraints - Interface in com.acmerobotics.roadrunner.profile
-
Motion profile motion constraints.
- MotionProfile - Class in com.acmerobotics.roadrunner.profile
-
Trapezoidal motion profile composed of motion segments.
- MotionProfile(segments) - Constructor for class com.acmerobotics.roadrunner.profile.MotionProfile
-
Trapezoidal motion profile composed of motion segments.
- MotionProfile() - 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.
- parameterDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- parameterDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- parameterDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- parameterSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- parameterSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- parameterSecondDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- parameterThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- parameterThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreeSplineSegment
-
- parameterThirdDeriv$module(t) - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- parametricCurve - Variable in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Base parametric curve
- ParametricCurve - Class in com.acmerobotics.roadrunner.path
-
Parametric curve with two components (x and y).
- ParametricCurve() - Constructor for class com.acmerobotics.roadrunner.path.ParametricCurve
-
Parametric curve with two components (x and y).
- Path - Class in com.acmerobotics.roadrunner.path
-
Path composed of a list of parametric curves and heading interpolators.
- Path(parametricCurves, interpolators, reversed) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
Path composed of a list of parametric curves and heading interpolators.
- Path(parametricCurves, interpolators) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
Path composed of a list of parametric curves and heading interpolators.
- Path(parametricCurves) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
Path composed of a list of parametric curves and heading interpolators.
- Path() - Constructor for class com.acmerobotics.roadrunner.path.Path
-
Path composed of a list of parametric curves and heading interpolators.
- Path(parametricCurve, interpolator, reversed) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
- Path(parametricCurve, interpolator) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
- Path(parametricCurve) - Constructor for class com.acmerobotics.roadrunner.path.Path
-
- Path.ProjectionResult - Class in com.acmerobotics.roadrunner.path
-
Simple container for the result of a projection (i.e., a
Path.project
call).
- PathBuilder - Class in com.acmerobotics.roadrunner.path
-
Easy-to-use builder for creating
class Path
instances.
- PathBuilder(startPose) - Constructor for class com.acmerobotics.roadrunner.path.PathBuilder
-
Easy-to-use builder for creating
class Path
instances.
- 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.
- PathTrajectorySegment - Class in com.acmerobotics.roadrunner.trajectory
-
Trajectory segment backed by a list of
class Path
objects.
- PathTrajectorySegment(paths, trajectoryConstraintsList, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
Trajectory segment backed by a list of
class Path
objects.
- PathTrajectorySegment(paths, trajectoryConstraintsList) - Constructor for class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
Trajectory segment backed by a list of
class Path
objects.
- PathTrajectorySegment(paths) - Constructor for class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
Trajectory segment backed by a list of
class Path
objects.
- PathTrajectorySegment() - Constructor for class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
Trajectory segment backed by a list of
class Path
objects.
- PathTrajectorySegment(path, trajectoryConstraints, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
- PathTrajectorySegment(path, trajectoryConstraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.PathTrajectorySegment
-
- PIDCoefficients - Class in com.acmerobotics.roadrunner.control
-
- PIDCoefficients(kP, kI, kD) - Constructor for class com.acmerobotics.roadrunner.control.PIDCoefficients
-
- PIDCoefficients() - Constructor for class com.acmerobotics.roadrunner.control.PIDCoefficients
-
- PIDFController - Class in com.acmerobotics.roadrunner.control
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV, kA, kStatic, kF) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV, kA, kStatic) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV, kA) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid, kV) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- PIDFController(pid) - Constructor for class com.acmerobotics.roadrunner.control.PIDFController
-
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward
control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
- plus(other) - Method in class com.acmerobotics.roadrunner.Pose2d
-
- plus(other) - Method in class com.acmerobotics.roadrunner.profile.MotionProfile
-
Returns a new motion profile with other concatenated.
- plus(other) - Method in class com.acmerobotics.roadrunner.Vector2d
-
- PointTurn - Class in com.acmerobotics.roadrunner.trajectory
-
Point turn trajectory segment.
- PointTurn(start, endHeading, constraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.PointTurn
-
Point turn trajectory segment.
- pos() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
- pos() - Method in class com.acmerobotics.roadrunner.Pose2d
-
- Pose2d - Class in com.acmerobotics.roadrunner
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(x, y, heading) - Constructor for class com.acmerobotics.roadrunner.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(x, y) - Constructor for class com.acmerobotics.roadrunner.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(x) - Constructor for class com.acmerobotics.roadrunner.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d() - Constructor for class com.acmerobotics.roadrunner.Pose2d
-
Class for representing 2D robot poses (x, y, and heading) and their derivatives.
- Pose2d(pos, heading) - Constructor for class com.acmerobotics.roadrunner.Pose2d
-
- Pose2dKt - Class in com.acmerobotics.roadrunner
-
- project(point, projectGuess) - Method in class com.acmerobotics.roadrunner.path.Path
-
Project point onto the current path.
- ProjectionResult(displacement, distance) - Constructor for class com.acmerobotics.roadrunner.path.Path.ProjectionResult
-
Simple container for the result of a projection (i.e., a
Path.project
call).
- RamseteFollower - Class in com.acmerobotics.roadrunner.followers
-
Time-varying, non-linear feedback controller for nonholonomic drives. See equation 5.12 of
Ramsete01.pdf.
- RamseteFollower(drive, b, zeta, kV, kA, kStatic, 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(drive, b, zeta, kV, kA, kStatic, 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(drive, b, zeta, kV, kA, kStatic, 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(drive, b, zeta, kV, kA, kStatic) - 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.drive.Kinematics
-
Performs a relative odometry update. Note: this assumes that the robot moves with constant velocity over the
measurement interval.
- reset() - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Reset the controller's integral sum.
- respectsDerivativeContinuity() - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
Returns true if the heading interpolator respects derivative continuity at path segment endpoints. That is,
the start and end heading derivatives match those of the
class TangentInterpolator
.
- respectsDerivativeContinuity() - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns true if the heading interpolator respects derivative continuity at path segment endpoints. That is,
the start and end heading derivatives match those of the
class TangentInterpolator
.
- respectsDerivativeContinuity() - Method in class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
-
Returns true if the heading interpolator respects derivative continuity at path segment endpoints. That is,
the start and end heading derivatives match those of the
class TangentInterpolator
.
- respectsDerivativeContinuity() - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Returns true if the heading interpolator respects derivative continuity at path segment endpoints. That is,
the start and end heading derivatives match those of the
class TangentInterpolator
.
- respectsDerivativeContinuity() - Method in class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
Returns true if the heading interpolator respects derivative continuity at path segment endpoints. That is,
the start and end heading derivatives match those of the
class TangentInterpolator
.
- respectsDerivativeContinuity() - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
Returns true if the heading interpolator respects derivative continuity at path segment endpoints. That is,
the start and end heading derivatives match those of the
class TangentInterpolator
.
- reverse() - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Reverse the direction of robot travel.
- reverse() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Reverse the direction of robot travel.
- 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(robotPoseAcceleration, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the acceleration vectors corresponding to robotPoseAcceleration given the provided trackWidth and
wheelBase.
- robotToModuleAccelerationVectors(robotPoseAcceleration, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the acceleration vectors corresponding to robotPoseAcceleration given the provided trackWidth and
wheelBase.
- robotToModuleAngularVelocities(robotPoseVelocity, robotPoseAcceleration, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the module angular velocities corresponding to robotPoseAcceleration given the provided trackWidth
and wheelBase.
- robotToModuleAngularVelocities(robotPoseVelocity, robotPoseAcceleration, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the module angular velocities corresponding to robotPoseAcceleration given the provided trackWidth
and wheelBase.
- robotToModuleOrientations(robotPoseVelocity, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the module orientations (in radians) corresponding to robotPoseVelocity given the provided
trackWidth and wheelBase.
- robotToModuleOrientations(robotPoseVelocity, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the module orientations (in radians) corresponding to robotPoseVelocity given the provided
trackWidth and wheelBase.
- robotToModuleVelocityVectors(robotPoseVelocity, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the wheel velocity vectors corresponding to robotPoseVelocity given the provided trackWidth and
wheelBase.
- robotToModuleVelocityVectors(robotPoseVelocity, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the wheel velocity vectors corresponding to robotPoseVelocity given the provided trackWidth and
wheelBase.
- robotToWheelAccelerations(robotPoseAcceleration, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.MecanumKinematics
-
Computes the wheel accelerations corresponding to robotPoseAcceleration given the provided trackWidth and
wheelBase.
- robotToWheelAccelerations(robotPoseAcceleration, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.MecanumKinematics
-
Computes the wheel accelerations corresponding to robotPoseAcceleration given the provided trackWidth and
wheelBase.
- robotToWheelAccelerations(robotPoseVelocity, robotPoseAcceleration, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the wheel accelerations corresponding to robotPoseAcceleration given the provided trackWidth and
wheelBase.
- robotToWheelAccelerations(robotPoseVelocity, robotPoseAcceleration, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the wheel accelerations corresponding to robotPoseAcceleration given the provided trackWidth and
wheelBase.
- robotToWheelAccelerations(robotPoseAcceleration, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.TankKinematics
-
Computes the wheel accelerations corresponding to robotPoseAcceleration given trackWidth.
- robotToWheelVelocities(robotPoseVelocity, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.MecanumKinematics
-
Computes the wheel velocities corresponding to robotPoseVelocity given the provided trackWidth and
wheelBase.
- robotToWheelVelocities(robotPoseVelocity, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.MecanumKinematics
-
Computes the wheel velocities corresponding to robotPoseVelocity given the provided trackWidth and
wheelBase.
- robotToWheelVelocities(robotPoseVelocity, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the wheel velocities corresponding to robotPoseVelocity given the provided trackWidth and
wheelBase.
- robotToWheelVelocities(robotPoseVelocity, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the wheel velocities corresponding to robotPoseVelocity given the provided trackWidth and
wheelBase.
- robotToWheelVelocities(robotPoseVelocity, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.TankKinematics
-
Computes the wheel velocities corresponding to robotPoseVelocity given trackWidth.
- rotated(angle) - Method in class com.acmerobotics.roadrunner.Vector2d
-
- saveConfig(trajectoryConfig, file) - Static method in class com.acmerobotics.roadrunner.trajectory.TrajectoryLoader
-
Saves trajectoryConfig to file.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.ConstantInterpolator
-
Returns the heading second derivative at the specified displacement.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Returns the heading second derivative at the specified displacement.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.LinearInterpolator
-
Returns the heading second derivative at the specified displacement.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Returns the heading second derivative at the specified displacement.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
Returns the heading second derivative at the specified displacement.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.heading.WiggleInterpolator
-
Returns the heading second derivative at the specified displacement.
- secondDeriv(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreePolynomial
-
Returns the second derivative of the polynomial at t.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the second derivative displacement units along the curve.
- secondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.Path
-
Returns the pose second derivative displacement units along the path.
- 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.QuinticSplineSegment.Waypoint
-
- seconds() - Method in class com.acmerobotics.roadrunner.util.NanoClock
-
Returns the number of seconds since an arbitrary (yet consistent) origin.
- 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
-
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.HolonomicPIDVAFollower
-
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.RamseteFollower
-
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.TankPIDVAFollower
-
- setLastError(p) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- setLocalizer(p) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
- setModuleOrientations(frontLeft, rearLeft, rearRight, frontRight) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Sets the module orientations. All values are in radians.
- setMotorPowers(frontLeft, rearLeft, rearRight, frontRight) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
Sets the following motor powers (normalized voltages). All arguments are on the interval [-1.0, 1.0]
.
- setMotorPowers(frontLeft, rearLeft, rearRight, frontRight) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Sets the following motor powers (normalized voltages). All arguments are on the interval [-1.0, 1.0]
.
- setMotorPowers(left, right) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
Sets the following motor powers (normalized voltages). All arguments are on the interval [-1.0, 1.0]
.
- setOutputBounds(min, max) - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Sets bounds on the output of the controller.
- setParametricCurve(p) - Method in class com.acmerobotics.roadrunner.path.heading.HeadingInterpolator
-
Base parametric curve
- setPath(p) - Method in class com.acmerobotics.roadrunner.followers.PathFollower
-
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
The robot's current pose estimate.
- setPoseEstimate(p) - Method in interface com.acmerobotics.roadrunner.drive.Localizer
-
Current robot 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(value) - Method in class com.acmerobotics.roadrunner.drive.ThreeTrackingWheelLocalizer
-
Current robot pose estimate.
- setPoseEstimate(value) - Method in class com.acmerobotics.roadrunner.drive.TwoTrackingWheelLocalizer
-
Current robot pose estimate.
- setReversed(reversed) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Sets the robot travel direction.
- setReversed(reversed) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Sets the robot travel direction.
- setTargetPosition(p) - Method in class com.acmerobotics.roadrunner.control.PIDFController
-
Target position (that is, the controller setpoint).
- setTrajectory(p) - Method in class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- setVelocity(poseVelocity) - Method in class com.acmerobotics.roadrunner.drive.Drive
-
Sets the poseVelocity of the robot.
- setVelocity(poseVelocity) - Method in class com.acmerobotics.roadrunner.drive.MecanumDrive
-
Sets the poseVelocity of the robot.
- setVelocity(poseVelocity) - Method in class com.acmerobotics.roadrunner.drive.SwerveDrive
-
Sets the poseVelocity of the robot.
- setVelocity(poseVelocity) - Method in class com.acmerobotics.roadrunner.drive.TankDrive
-
Sets the poseVelocity of the robot.
- SimpleMotionConstraints - Class in com.acmerobotics.roadrunner.profile
-
- SimpleMotionConstraints(maximumVelocity, maximumAcceleration) - Constructor for class com.acmerobotics.roadrunner.profile.SimpleMotionConstraints
-
- solveQuadratic(a, b, c) - Static method in class com.acmerobotics.roadrunner.util.MathUtil
-
Returns the real solutions to the quadratic ax^2 + bx + c.
- SplineInterpolator - Class in com.acmerobotics.roadrunner.path.heading
-
Spline heading interpolator for transitioning smoothly between headings without violating continuity (and hence
allowing for integration into longer profiles).
- SplineInterpolator(startHeading, endHeading) - Constructor for class com.acmerobotics.roadrunner.path.heading.SplineInterpolator
-
Spline heading interpolator for transitioning smoothly between headings without violating continuity (and hence
allowing for integration into longer profiles).
- splineTo(pose, interpolator) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a spline segment.
- splineTo(pose) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a spline segment.
- splineTo(pose, interpolator, constraintsOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a spline segment.
- splineTo(pose, interpolator) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a spline segment.
- splineTo(pose) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a spline segment.
- 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.profile.MotionProfile
-
- start() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
Returns the start pose.
- startAcceleration() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
Returns the start pose acceleration.
- 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.
- 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.
- startThirdDeriv() - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the start third derivative.
- startVelocity() - Method in class com.acmerobotics.roadrunner.trajectory.Trajectory
-
Returns the start pose velocity.
- 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.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.TrajectoryBuilder
-
Adds a segment that strafes right in the robot reference frame.
- strafeTo(pos) - Method in class com.acmerobotics.roadrunner.path.PathBuilder
-
Adds a strafe path segment.
- strafeTo(pos) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a strafe path segment.
- SwerveConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- SwerveConstraints(baseConstraints, trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.SwerveConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- SwerveConstraints(baseConstraints, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.SwerveConstraints
-
Mecanum-specific drive constraints that also limit maximum wheel velocities.
- SwerveDrive - Class in com.acmerobotics.roadrunner.drive
-
- SwerveDrive(trackWidth, wheelBase) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- SwerveDrive(trackWidth) - Constructor for class com.acmerobotics.roadrunner.drive.SwerveDrive
-
- SwerveDrive.SwerveLocalizer - Class in com.acmerobotics.roadrunner.drive
-
Default localizer for swerve drives based on the drive encoder positions, module orientations, and (optionally) a
heading sensor.
- SwerveKinematics - Class in com.acmerobotics.roadrunner.drive
-
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.
- SwervePIDVAFollower - 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.
- SwervePIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic, admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.SwervePIDVAFollower
-
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.
- SwervePIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic, admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.SwervePIDVAFollower
-
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.
- SwervePIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic, admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.SwervePIDVAFollower
-
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.
- SwervePIDVAFollower(drive, translationalCoeffs, headingCoeffs, kV, kA, kStatic) - Constructor for class com.acmerobotics.roadrunner.followers.SwervePIDVAFollower
-
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.
- system() - Method in class com.acmerobotics.roadrunner.util.NanoClock.Companion
-
- system() - Static method in class com.acmerobotics.roadrunner.util.NanoClock
-
- tangentAngle(displacement) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the angle of the tangent line displacement units along the curve.
- tangentAngleDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the derivative of the tangent angle displacement units along the curve.
- tangentAngleSecondDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the second derivative of the tangent angle displacement units along the curve.
- TangentInterpolator - Class in com.acmerobotics.roadrunner.path.heading
-
Tangent (system) interpolator for tank/differential and other nonholonomic drives.
- TangentInterpolator() - Constructor for class com.acmerobotics.roadrunner.path.heading.TangentInterpolator
-
Tangent (system) interpolator for tank/differential and other nonholonomic drives.
- TankConstraints - Class in com.acmerobotics.roadrunner.trajectory.constraints
-
Tank-specific drive constraints that also limit maximum wheel velocities.
- TankConstraints(baseConstraints, trackWidth) - Constructor for class com.acmerobotics.roadrunner.trajectory.constraints.TankConstraints
-
Tank-specific drive constraints that also limit maximum wheel velocities.
- TankDrive - Class in com.acmerobotics.roadrunner.drive
-
This class provides the basic functionality of a tank/differential drive using
class TankKinematics
.
- TankDrive(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.drive
-
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 MecanumPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(drive, displacementCoeffs, crossTrackCoeffs, kV, kA, kStatic, 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 MecanumPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(drive, displacementCoeffs, crossTrackCoeffs, kV, kA, kStatic, 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 MecanumPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(drive, displacementCoeffs, crossTrackCoeffs, kV, kA, kStatic, 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 MecanumPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- TankPIDVAFollower(drive, displacementCoeffs, crossTrackCoeffs, kV, kA, kStatic) - 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 MecanumPIDVAFollower
except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level.
- thirdDeriv(t) - Method in class com.acmerobotics.roadrunner.path.NthDegreePolynomial
-
Returns the third derivative of the polynomial at t.
- thirdDeriv(displacement) - Method in class com.acmerobotics.roadrunner.path.ParametricCurve
-
Returns the third derivative displacement 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.drive
-
Localizer based on three unpowered tracking omni wheels.
- ThreeTrackingWheelLocalizer(wheelPositions, wheelOrientations) - Constructor for class com.acmerobotics.roadrunner.drive.ThreeTrackingWheelLocalizer
-
Localizer based on three unpowered tracking omni wheels.
- times(scalar) - Method in class com.acmerobotics.roadrunner.Pose2d
-
- times($receiver, pose) - Static method in class com.acmerobotics.roadrunner.Pose2dKt
-
- times(scalar) - Method in class com.acmerobotics.roadrunner.Vector2d
-
- times($receiver, vector) - Static method in class com.acmerobotics.roadrunner.Vector2dKt
-
- toString() - Method in class com.acmerobotics.roadrunner.path.LineSegment
-
- toString() - Method in class com.acmerobotics.roadrunner.path.Path.ProjectionResult
-
- toString() - Method in class com.acmerobotics.roadrunner.path.QuinticPolynomial
-
- toString() - Method in class com.acmerobotics.roadrunner.path.QuinticSplineSegment
-
- toString() - Method in class com.acmerobotics.roadrunner.Pose2d
-
- 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.Vector2d
-
- toTrajectory() - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
- Trajectory - Class in com.acmerobotics.roadrunner.trajectory
-
Time-parametrized trajectory of poses.
- Trajectory(segments) - Constructor for class com.acmerobotics.roadrunner.trajectory.Trajectory
-
Time-parametrized trajectory of poses.
- Trajectory() - Constructor for class com.acmerobotics.roadrunner.trajectory.Trajectory
-
Time-parametrized trajectory of poses.
- TrajectoryBuilder - Class in com.acmerobotics.roadrunner.trajectory
-
- TrajectoryBuilder(startPose, globalConstraints, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
- TrajectoryBuilder(startPose, globalConstraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
- TrajectoryConfig - Class in com.acmerobotics.roadrunner.trajectory
-
Basic trajectory configuration intended for serialization. Intentionally more simplistic and less flexible than
class TrajectoryBuilder
.
- TrajectoryConfig(poses, constraints, resolution) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
Basic trajectory configuration intended for serialization. Intentionally more simplistic and less flexible than
class TrajectoryBuilder
.
- TrajectoryConfig(poses, constraints) - Constructor for class com.acmerobotics.roadrunner.trajectory.TrajectoryConfig
-
Basic trajectory configuration intended for serialization. Intentionally more simplistic and less flexible than
class TrajectoryBuilder
.
- TrajectoryConstraints - Interface in com.acmerobotics.roadrunner.trajectory.constraints
-
Trajectory-specific constraints for motion profile generation.
- TrajectoryFollower - Class in com.acmerobotics.roadrunner.followers
-
- TrajectoryFollower(admissibleError, timeout, clock) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryFollower(admissibleError, timeout) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryFollower(admissibleError) - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryFollower() - Constructor for class com.acmerobotics.roadrunner.followers.TrajectoryFollower
-
- TrajectoryLoader - Class in com.acmerobotics.roadrunner.trajectory
-
- TrajectorySegment - Interface in com.acmerobotics.roadrunner.trajectory
-
Generic trajectory segment.
- turn(angle, constraintsOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a point turn.
- turn(angle) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a point turn.
- turnTo(heading, constraintsOverride) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a point turn.
- turnTo(heading) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a point turn.
- TwoTrackingWheelLocalizer - Class in com.acmerobotics.roadrunner.drive
-
Localizer based on two unpowered tracking omni wheels and an orientation sensor.
- TwoTrackingWheelLocalizer(wheelPositions, wheelOrientations) - Constructor for class com.acmerobotics.roadrunner.drive.TwoTrackingWheelLocalizer
-
Localizer based on two unpowered tracking omni wheels and an orientation sensor.
- waitFor(duration) - Method in class com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
-
Adds a wait segment.
- WaitSegment - Class in com.acmerobotics.roadrunner.trajectory
-
Static trajectory segment that holds a constant pose. Used for giving trajectories extra time to settle.
- WaitSegment(pose, duration) - Constructor for class com.acmerobotics.roadrunner.trajectory.WaitSegment
-
Static trajectory segment that holds a constant pose. Used for giving trajectories extra time to settle.
- Waypoint(x, y, dx, dy, d2x, d2y) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
Class for representing the end points of interpolated quintic splines.
- Waypoint(x, y, dx, dy, d2x) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
Class for representing the end points of interpolated quintic splines.
- Waypoint(x, y, dx, dy) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
Class for representing the end points of interpolated quintic splines.
- Waypoint(x, y, dx) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
Class for representing the end points of interpolated quintic splines.
- Waypoint(x, y) - Constructor for class com.acmerobotics.roadrunner.path.QuinticSplineSegment.Waypoint
-
Class for representing the end points of interpolated quintic splines.
- wheelToRobotVelocities(wheelVelocities, trackWidth, wheelBase) - Static method in class com.acmerobotics.roadrunner.drive.MecanumKinematics
-
Computes the robot velocity corresponding to wheelVelocities and the given drive parameters.
- wheelToRobotVelocities(wheelVelocities, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.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.drive.SwerveKinematics
-
Computes the robot velocities corresponding to wheelVelocities, moduleOrientations, and the drive parameters.
- wheelToRobotVelocities(wheelVelocities, moduleOrientations, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.SwerveKinematics
-
Computes the robot velocities corresponding to wheelVelocities, moduleOrientations, and the drive parameters.
- wheelToRobotVelocities(wheelVelocities, trackWidth) - Static method in class com.acmerobotics.roadrunner.drive.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
-