Class DifferentialDriveVoltageConstraint

java.lang.Object
edu.wpi.first.math.trajectory.constraint.DifferentialDriveVoltageConstraint
All Implemented Interfaces:
TrajectoryConstraint

A class that enforces constraints on differential drive voltage expenditure based on the motor dynamics and the drive kinematics. Ensures that the acceleration of any wheel of the robot while following the trajectory is never higher than what can be achieved with the given maximum voltage.
  • Constructor Details

    • DifferentialDriveVoltageConstraint

      public DifferentialDriveVoltageConstraint(SimpleMotorFeedforward feedforward, DifferentialDriveKinematics kinematics, double maxVoltage)
      Creates a new DifferentialDriveVoltageConstraint.
      Parameters:
      feedforward - A feedforward component describing the behavior of the drive.
      kinematics - A kinematics component describing the drive geometry.
      maxVoltage - The maximum voltage available to the motors while following the path. Should be somewhat less than the nominal battery voltage (12V) to account for "voltage sag" due to current draw.
  • Method Details

    • getMaxVelocityMetersPerSecond

      public double getMaxVelocityMetersPerSecond(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)
      Description copied from interface: TrajectoryConstraint
      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)
      Description copied from interface: TrajectoryConstraint
      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.