Class PPHolonomicDriveController

java.lang.Object
com.pathplanner.lib.controllers.PPHolonomicDriveController
All Implemented Interfaces:
PathFollowingController

public class PPHolonomicDriveController extends Object implements PathFollowingController
Path following controller for holonomic drive trains
  • Constructor Details

    • PPHolonomicDriveController

      public PPHolonomicDriveController(PIDConstants translationConstants, PIDConstants rotationConstants, double period)
      Constructs a HolonomicDriveController
      Parameters:
      translationConstants - PID constants for the translation PID controllers
      rotationConstants - PID constants for the rotation controller
      period - Period of the control loop in seconds
    • PPHolonomicDriveController

      public PPHolonomicDriveController(PIDConstants translationConstants, PIDConstants rotationConstants)
      Constructs a HolonomicDriveController
      Parameters:
      translationConstants - PID constants for the translation PID controllers
      rotationConstants - PID constants for the rotation controller
  • Method Details

    • setEnabled

      public void setEnabled(boolean enabled)
      Enables and disables the controller for troubleshooting. When calculate() is called on a disabled controller, only feedforward values are returned.
      Parameters:
      enabled - If the controller is enabled or not
    • reset

      public void reset(Pose2d currentPose, ChassisSpeeds currentSpeeds)
      Resets the controller based on the current state of the robot
      Specified by:
      reset in interface PathFollowingController
      Parameters:
      currentPose - Current robot pose
      currentSpeeds - Current robot relative chassis speeds
    • calculateRobotRelativeSpeeds

      public ChassisSpeeds calculateRobotRelativeSpeeds(Pose2d currentPose, PathPlannerTrajectoryState targetState)
      Calculates the next output of the path following controller
      Specified by:
      calculateRobotRelativeSpeeds in interface PathFollowingController
      Parameters:
      currentPose - The current robot pose
      targetState - The desired trajectory state
      Returns:
      The next robot relative output of the path following controller
    • isHolonomic

      public boolean isHolonomic()
      Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.
      Specified by:
      isHolonomic in interface PathFollowingController
      Returns:
      True if this controller is for a holonomic drive train
    • setRotationTargetOverride

      @Deprecated public static void setRotationTargetOverride(Supplier<Optional<Rotation2d>> rotationTargetOverride)
      Deprecated.
      Use overrideRotationFeedback instead, with the output of your own PID controller
      Set a supplier that will be used to override the rotation target when path following.

      This function should return an empty optional to use the rotation targets in the path

      Parameters:
      rotationTargetOverride - Supplier to override rotation targets
    • overrideXFeedback

      public static void overrideXFeedback(DoubleSupplier xFeedbackOverride)
      Begin overriding the X axis feedback.
      Parameters:
      xFeedbackOverride - Double supplier that returns the desired FIELD-RELATIVE X feedback in meters/sec
    • clearXFeedbackOverride

      public static void clearXFeedbackOverride()
      Stop overriding the X axis feedback, and return to calculating it based on path following error.
    • overrideYFeedback

      public static void overrideYFeedback(DoubleSupplier yFeedbackOverride)
      Begin overriding the Y axis feedback.
      Parameters:
      yFeedbackOverride - Double supplier that returns the desired FIELD-RELATIVE Y feedback in meters/sec
    • clearYFeedbackOverride

      public static void clearYFeedbackOverride()
      Stop overriding the Y axis feedback, and return to calculating it based on path following error.
    • overrideXYFeedback

      public static void overrideXYFeedback(DoubleSupplier xFeedbackOverride, DoubleSupplier yFeedbackOverride)
      Begin overriding the X and Y axis feedback.
      Parameters:
      xFeedbackOverride - Double supplier that returns the desired FIELD-RELATIVE X feedback in meters/sec
      yFeedbackOverride - Double supplier that returns the desired FIELD-RELATIVE Y feedback in meters/sec
    • clearXYFeedbackOverride

      public static void clearXYFeedbackOverride()
      Stop overriding the X and Y axis feedback, and return to calculating them based on path following error.
    • overrideRotationFeedback

      public static void overrideRotationFeedback(DoubleSupplier rotationFeedbackOverride)
      Begin overriding the rotation feedback.
      Parameters:
      rotationFeedbackOverride - Double supplier that returns the desired rotation feedback in radians/sec
    • clearRotationFeedbackOverride

      public static void clearRotationFeedbackOverride()
      Stop overriding the rotation feedback, and return to calculating it based on path following error.
    • clearFeedbackOverrides

      public static void clearFeedbackOverrides()
      Clear all feedback overrides and return to purely using path following error for feedback