50 : m_xController(
std::move(xController)),
51 m_yController(
std::move(yController)),
52 m_thetaController(
std::move(thetaController)) {
53 m_thetaController.EnableContinuousInput(0_deg, 360.0_deg);
67 const auto& eTranslate = m_poseError.Translation();
68 const auto& eRotate = m_rotationError;
69 const auto& tolTranslate = m_poseTolerance.Translation();
70 const auto& tolRotate = m_poseTolerance.Rotation();
83 m_poseTolerance = tolerance;
99 units::meters_per_second_t desiredLinearVelocity,
109 auto xFF = desiredLinearVelocity * trajectoryPose.
Rotation().
Cos();
110 auto yFF = desiredLinearVelocity * trajectoryPose.
Rotation().
Sin();
111 auto thetaFF = units::radians_per_second_t{m_thetaController.Calculate(
114 m_poseError = trajectoryPose.
RelativeTo(currentPose);
115 m_rotationError = desiredHeading - currentPose.
Rotation();
118 return ChassisSpeeds::FromFieldRelativeSpeeds(xFF, yFF, thetaFF,
123 auto xFeedback = units::meters_per_second_t{m_xController.Calculate(
124 currentPose.
X().value(), trajectoryPose.
X().value())};
125 auto yFeedback = units::meters_per_second_t{m_yController.Calculate(
126 currentPose.
Y().value(), trajectoryPose.
Y().value())};
129 return ChassisSpeeds::FromFieldRelativeSpeeds(
130 xFF + xFeedback, yFF + yFeedback, thetaFF, currentPose.
Rotation());
146 return Calculate(currentPose, desiredState.
pose, desiredState.
velocity,
157 constexpr void SetEnabled(
bool enabled) { m_enabled = enabled; }
164 [[deprecated(
"Use GetXController() instead")]]
166 return m_xController;
174 [[deprecated(
"Use GetYController() instead")]]
176 return m_yController;
184 [[deprecated(
"Use GetThetaController() instead")]]
186 return m_thetaController;
203 return m_thetaController;
210 bool m_enabled =
true;
216 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:35
constexpr void SetTolerance(const Pose2d &tolerance)
Sets the pose error which is considered tolerable for use with AtReference().
Definition HolonomicDriveController.h:82
constexpr PIDController & GetYController()
Returns the Y PIDController.
Definition HolonomicDriveController.h:197
constexpr HolonomicDriveController(HolonomicDriveController &&)=default
constexpr ProfiledPIDController< units::radian > & getThetaController()
Returns the rotation ProfiledPIDController.
Definition HolonomicDriveController.h:185
constexpr HolonomicDriveController & operator=(const HolonomicDriveController &)=default
constexpr ProfiledPIDController< units::radian > & GetThetaController()
Returns the rotation ProfiledPIDController.
Definition HolonomicDriveController.h:202
constexpr PIDController & getYController()
Returns the Y PIDController.
Definition HolonomicDriveController.h:175
constexpr 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.
Definition HolonomicDriveController.h:97
constexpr ChassisSpeeds Calculate(const Pose2d ¤tPose, const Trajectory::State &desiredState, const Rotation2d &desiredHeading)
Returns the next output of the holonomic drive controller.
Definition HolonomicDriveController.h:143
constexpr HolonomicDriveController(const HolonomicDriveController &)=default
constexpr bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
Definition HolonomicDriveController.h:66
constexpr void SetEnabled(bool enabled)
Enables and disables the controller for troubleshooting purposes.
Definition HolonomicDriveController.h:157
constexpr PIDController & GetXController()
Returns the X PIDController.
Definition HolonomicDriveController.h:192
constexpr HolonomicDriveController(PIDController xController, PIDController yController, ProfiledPIDController< units::radian > thetaController)
Constructs a holonomic drive controller.
Definition HolonomicDriveController.h:47
constexpr HolonomicDriveController & operator=(HolonomicDriveController &&)=default
constexpr PIDController & getXController()
Returns the X PIDController.
Definition HolonomicDriveController.h:165
Implements a PID control loop.
Definition PIDController.h:29
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition Pose2d.h:128
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose2d.h:121
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose2d.h:114
constexpr Pose2d RelativeTo(const Pose2d &other) const
Returns the current pose relative to the given pose.
Definition Pose2d.h:318
Implements a PID control loop whose setpoint is constrained by a trapezoid profile.
Definition ProfiledPIDController.h:34
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:231
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.h:238
constexpr units::radian_t Radians() const
Returns the radian value of the rotation.
Definition Rotation2d.h:216
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
Implement std::hash so that hash_code can be used in STL containers.
Definition PointerIntPair.h:280
Represents the speed of a robot chassis.
Definition ChassisSpeeds.h:25
Represents one point on the trajectory.
Definition Trajectory.h:34
Pose2d pose
The pose at that point of the trajectory.
Definition Trajectory.h:45
units::meters_per_second_t velocity
The speed at that point of the trajectory.
Definition Trajectory.h:39