Class SwerveDriveKinematicsConstraint
java.lang.Object
edu.wpi.first.math.trajectory.constraint.SwerveDriveKinematicsConstraint
- All Implemented Interfaces:
TrajectoryConstraint
public class SwerveDriveKinematicsConstraint extends Object implements TrajectoryConstraint
A class that enforces constraints on the swerve drive kinematics. This can be used to ensure that
the trajectory is constructed so that the commanded velocities for all 4 wheels of the drivetrain
stay below a certain limit.
-
Nested Class Summary
Nested classes/interfaces inherited from interface edu.wpi.first.math.trajectory.constraint.TrajectoryConstraint
TrajectoryConstraint.MinMax -
Constructor Summary
Constructors Constructor Description SwerveDriveKinematicsConstraint(SwerveDriveKinematics kinematics, double maxSpeedMetersPerSecond)Constructs a swerve drive kinematics constraint. -
Method Summary
Modifier and Type Method Description doublegetMaxVelocityMetersPerSecond(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)Returns the max velocity given the current pose and curvature.TrajectoryConstraint.MinMaxgetMinMaxAccelerationMetersPerSecondSq(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
-
Constructor Details
-
SwerveDriveKinematicsConstraint
public SwerveDriveKinematicsConstraint(SwerveDriveKinematics kinematics, double maxSpeedMetersPerSecond)Constructs a swerve drive kinematics constraint.- Parameters:
kinematics- Swerve drive kinematics.maxSpeedMetersPerSecond- The max speed that a side of the robot can travel at.
-
-
Method Details
-
getMaxVelocityMetersPerSecond
public double getMaxVelocityMetersPerSecond(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)Returns the max velocity given the current pose and curvature.- Specified by:
getMaxVelocityMetersPerSecondin interfaceTrajectoryConstraint- Parameters:
poseMeters- The pose at the current point in the trajectory.curvatureRadPerMeter- The curvature at the current point in the trajectory.velocityMetersPerSecond- The velocity at the current point in the trajectory before constraints are applied.- Returns:
- The absolute maximum velocity.
-
getMinMaxAccelerationMetersPerSecondSq
public TrajectoryConstraint.MinMax getMinMaxAccelerationMetersPerSecondSq(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.- Specified by:
getMinMaxAccelerationMetersPerSecondSqin interfaceTrajectoryConstraint- Parameters:
poseMeters- The pose at the current point in the trajectory.curvatureRadPerMeter- The curvature at the current point in the trajectory.velocityMetersPerSecond- The speed at the current point in the trajectory.- Returns:
- The min and max acceleration bounds.
-