WPILibC++ 2023.4.3
frc::HolonomicDriveController Class Reference

This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i.e. More...

#include <frc/controller/HolonomicDriveController.h>

Public Member Functions

 HolonomicDriveController (frc2::PIDController xController, frc2::PIDController yController, ProfiledPIDController< units::radian > thetaController)
 Constructs a holonomic drive controller. More...
 
 HolonomicDriveController (const HolonomicDriveController &)=default
 
HolonomicDriveControlleroperator= (const HolonomicDriveController &)=default
 
 HolonomicDriveController (HolonomicDriveController &&)=default
 
HolonomicDriveControlleroperator= (HolonomicDriveController &&)=default
 
bool AtReference () const
 Returns true if the pose error is within tolerance of the reference. More...
 
void SetTolerance (const Pose2d &tolerance)
 Sets the pose error which is considered tolerable for use with AtReference(). More...
 
ChassisSpeeds Calculate (const Pose2d &currentPose, const Pose2d &trajectoryPose, units::meters_per_second_t desiredLinearVelocity, const Rotation2d &desiredHeading)
 Returns the next output of the holonomic drive controller. More...
 
ChassisSpeeds Calculate (const Pose2d &currentPose, const Trajectory::State &desiredState, const Rotation2d &desiredHeading)
 Returns the next output of the holonomic drive controller. More...
 
void SetEnabled (bool enabled)
 Enables and disables the controller for troubleshooting purposes. More...
 
ProfiledPIDController< units::radian > & getThetaController ()
 Returns the rotation ProfiledPIDController. More...
 
PIDControllergetXController ()
 Returns the X PIDController. More...
 
PIDControllergetYController ()
 Returns the Y PIDController. More...
 

Detailed Description

This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i.e.

swerve or mecanum). Holonomic trajectory following is a much simpler problem to solve compared to skid-steer style drivetrains because it is possible to individually control forward, sideways, and angular velocity.

The holonomic drive controller takes in one PID controller for each direction, forward and sideways, and one profiled PID controller for the angular direction. Because the heading dynamics are decoupled from translations, users can specify a custom heading that the drivetrain should point toward. This heading reference is profiled for smoothness.

Constructor & Destructor Documentation

◆ HolonomicDriveController() [1/3]

frc::HolonomicDriveController::HolonomicDriveController ( frc2::PIDController  xController,
frc2::PIDController  yController,
ProfiledPIDController< units::radian >  thetaController 
)

Constructs a holonomic drive controller.

Parameters
xControllerA PID Controller to respond to error in the field-relative x direction.
yControllerA PID Controller to respond to error in the field-relative y direction.
thetaControllerA profiled PID controller to respond to error in angle.

◆ HolonomicDriveController() [2/3]

frc::HolonomicDriveController::HolonomicDriveController ( const HolonomicDriveController )
default

◆ HolonomicDriveController() [3/3]

frc::HolonomicDriveController::HolonomicDriveController ( HolonomicDriveController &&  )
default

Member Function Documentation

◆ AtReference()

bool frc::HolonomicDriveController::AtReference ( ) const

Returns true if the pose error is within tolerance of the reference.

◆ Calculate() [1/2]

ChassisSpeeds frc::HolonomicDriveController::Calculate ( const Pose2d currentPose,
const Pose2d trajectoryPose,
units::meters_per_second_t  desiredLinearVelocity,
const Rotation2d desiredHeading 
)

Returns the next output of the holonomic drive controller.

Parameters
currentPoseThe current pose, as measured by odometry or pose estimator.
trajectoryPoseThe desired trajectory pose, as sampled for the current timestep.
desiredLinearVelocityThe desired linear velocity.
desiredHeadingThe desired heading.
Returns
The next output of the holonomic drive controller.

◆ Calculate() [2/2]

ChassisSpeeds frc::HolonomicDriveController::Calculate ( const Pose2d currentPose,
const Trajectory::State desiredState,
const Rotation2d desiredHeading 
)

Returns the next output of the holonomic drive controller.

Parameters
currentPoseThe current pose, as measured by odometry or pose estimator.
desiredStateThe desired trajectory pose, as sampled for the current timestep.
desiredHeadingThe desired heading.
Returns
The next output of the holonomic drive controller.

◆ getThetaController()

ProfiledPIDController< units::radian > & frc::HolonomicDriveController::getThetaController ( )

Returns the rotation ProfiledPIDController.

◆ getXController()

PIDController & frc::HolonomicDriveController::getXController ( )

Returns the X PIDController.

◆ getYController()

PIDController & frc::HolonomicDriveController::getYController ( )

Returns the Y PIDController.

◆ operator=() [1/2]

HolonomicDriveController & frc::HolonomicDriveController::operator= ( const HolonomicDriveController )
default

◆ operator=() [2/2]

HolonomicDriveController & frc::HolonomicDriveController::operator= ( HolonomicDriveController &&  )
default

◆ SetEnabled()

void frc::HolonomicDriveController::SetEnabled ( bool  enabled)

Enables and disables the controller for troubleshooting purposes.

When Calculate() is called on a disabled controller, only feedforward values are returned.

Parameters
enabledIf the controller is enabled or not.

◆ SetTolerance()

void frc::HolonomicDriveController::SetTolerance ( const Pose2d tolerance)

Sets the pose error which is considered tolerable for use with AtReference().

Parameters
tolerancePose error which is tolerable.

The documentation for this class was generated from the following file: