WPILibC++ 2023.4.3-108-ge5452e3
|
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 | |
HolonomicDriveController & | operator= (const HolonomicDriveController &)=default |
HolonomicDriveController (HolonomicDriveController &&)=default | |
HolonomicDriveController & | operator= (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 ¤tPose, 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 ¤tPose, 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... | |
PIDController & | getXController () |
Returns the X PIDController. More... | |
PIDController & | getYController () |
Returns the Y PIDController. More... | |
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.
frc::HolonomicDriveController::HolonomicDriveController | ( | frc2::PIDController | xController, |
frc2::PIDController | yController, | ||
ProfiledPIDController< units::radian > | thetaController | ||
) |
Constructs a holonomic drive controller.
xController | A PID Controller to respond to error in the field-relative x direction. |
yController | A PID Controller to respond to error in the field-relative y direction. |
thetaController | A profiled PID controller to respond to error in angle. |
|
default |
|
default |
bool frc::HolonomicDriveController::AtReference | ( | ) | const |
Returns true if the pose error is within tolerance of the reference.
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.
currentPose | The current pose, as measured by odometry or pose estimator. |
trajectoryPose | The desired trajectory pose, as sampled for the current timestep. |
desiredLinearVelocity | The desired linear velocity. |
desiredHeading | The desired heading. |
ChassisSpeeds frc::HolonomicDriveController::Calculate | ( | const Pose2d & | currentPose, |
const Trajectory::State & | desiredState, | ||
const Rotation2d & | desiredHeading | ||
) |
Returns the next output of the holonomic drive controller.
currentPose | The current pose, as measured by odometry or pose estimator. |
desiredState | The desired trajectory pose, as sampled for the current timestep. |
desiredHeading | The desired heading. |
ProfiledPIDController< units::radian > & frc::HolonomicDriveController::getThetaController | ( | ) |
Returns the rotation ProfiledPIDController.
PIDController & frc::HolonomicDriveController::getXController | ( | ) |
Returns the X PIDController.
PIDController & frc::HolonomicDriveController::getYController | ( | ) |
Returns the Y PIDController.
|
default |
|
default |
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.
enabled | If the controller is enabled or not. |
void frc::HolonomicDriveController::SetTolerance | ( | const Pose2d & | tolerance | ) |
Sets the pose error which is considered tolerable for use with AtReference().
tolerance | Pose error which is tolerable. |