Class 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.
    • Constructor Detail

      • SwerveDriveKinematicsConstraint

        public SwerveDriveKinematicsConstraint​(SwerveDriveKinematics kinematics,
                                               double maxSpeedMetersPerSecond)
        Constructs a swerve drive dynamics constraint.
        Parameters:
        maxSpeedMetersPerSecond - The max speed that a side of the robot can travel at.
    • Method Detail

      • getMaxVelocityMetersPerSecond

        public double getMaxVelocityMetersPerSecond​(Pose2d poseMeters,
                                                    double curvatureRadPerMeter,
                                                    double velocityMetersPerSecond)
        Returns the max velocity given the current pose and curvature.
        Specified by:
        getMaxVelocityMetersPerSecond in interface TrajectoryConstraint
        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:
        getMinMaxAccelerationMetersPerSecondSq in interface TrajectoryConstraint
        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.