Class DifferentialDriveKinematicsConstraint
java.lang.Object
org.wpilib.math.trajectory.constraint.DifferentialDriveKinematicsConstraint
- All Implemented Interfaces:
TrajectoryConstraint
A class that enforces constraints on the differential drive kinematics. This can be used to
ensure that the trajectory is constructed so that the commanded velocities for both sides of the
drivetrain stay below a certain limit.
-
Nested Class Summary
Nested classes/interfaces inherited from interface TrajectoryConstraint
TrajectoryConstraint.MinMax -
Constructor Summary
ConstructorsConstructorDescriptionDifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics, double maxVelocity) Constructs a differential drive dynamics constraint. -
Method Summary
Modifier and TypeMethodDescriptiondoublegetMaxVelocity(Pose2d pose, double curvature, double velocity) Returns the max velocity given the current pose and curvature.getMinMaxAcceleration(Pose2d pose, double curvature, double velocity) Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity.
-
Constructor Details
-
DifferentialDriveKinematicsConstraint
public DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics, double maxVelocity) Constructs a differential drive dynamics constraint.- Parameters:
kinematics- A kinematics component describing the drive geometry.maxVelocity- The max velocity that a side of the robot can travel at in m/s.
-
-
Method Details
-
getMaxVelocity
Returns the max velocity given the current pose and curvature.- Specified by:
getMaxVelocityin interfaceTrajectoryConstraint- Parameters:
pose- The pose at the current point in the trajectory.curvature- The curvature at the current point in the trajectory in rad/m.velocity- The velocity at the current point in the trajectory before constraints are applied in m/s.- Returns:
- The absolute maximum velocity.
-
getMinMaxAcceleration
public TrajectoryConstraint.MinMax getMinMaxAcceleration(Pose2d pose, double curvature, double velocity) Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity.- Specified by:
getMinMaxAccelerationin interfaceTrajectoryConstraint- Parameters:
pose- The pose at the current point in the trajectory.curvature- The curvature at the current point in the trajectory in rad/m.velocity- The velocity at the current point in the trajectory in m/s.- Returns:
- The min and max acceleration bounds.
-