79 const Pose2d& trajectoryPose,
80 units::meters_per_second_t desiredLinearVelocity,
125 bool m_enabled =
true;
131 bool m_firstRun =
true;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i....
Definition: HolonomicDriveController.h:32
PIDController & getYController()
Returns the Y PIDController.
ProfiledPIDController< units::radian > & getThetaController()
Returns the rotation ProfiledPIDController.
ChassisSpeeds Calculate(const Pose2d ¤tPose, const Trajectory::State &desiredState, const Rotation2d &desiredHeading)
Returns the next output of the holonomic drive controller.
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.
void SetTolerance(const Pose2d &tolerance)
Sets the pose error which is considered tolerable for use with AtReference().
void SetEnabled(bool enabled)
Enables and disables the controller for troubleshooting purposes.
bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
HolonomicDriveController & operator=(HolonomicDriveController &&)=default
HolonomicDriveController & operator=(const HolonomicDriveController &)=default
HolonomicDriveController(const HolonomicDriveController &)=default
PIDController & getXController()
Returns the X PIDController.
HolonomicDriveController(HolonomicDriveController &&)=default
HolonomicDriveController(PIDController xController, PIDController yController, ProfiledPIDController< units::radian > thetaController)
Constructs a holonomic drive controller.
Implements a PID control loop.
Definition: PIDController.h:23
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Definition: AprilTagPoseEstimator.h:15
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
Represents one point on the trajectory.
Definition: Trajectory.h:30