WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
HolonomicDriveController.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <utility>
8
9#include <wpi/SymbolExports.h>
10
13#include "frc/geometry/Pose2d.h"
17#include "units/angle.h"
19#include "units/velocity.h"
20
21namespace frc {
22/**
23 * This holonomic drive controller can be used to follow trajectories using a
24 * holonomic drivetrain (i.e. swerve or mecanum). Holonomic trajectory following
25 * is a much simpler problem to solve compared to skid-steer style drivetrains
26 * because it is possible to individually control forward, sideways, and angular
27 * velocity.
28 *
29 * The holonomic drive controller takes in one PID controller for each
30 * direction, forward and sideways, and one profiled PID controller for the
31 * angular direction. Because the heading dynamics are decoupled from
32 * translations, users can specify a custom heading that the drivetrain should
33 * point toward. This heading reference is profiled for smoothness.
34 */
36 public:
37 /**
38 * Constructs a holonomic drive controller.
39 *
40 * @param xController A PID Controller to respond to error in the
41 * field-relative x direction.
42 * @param yController A PID Controller to respond to error in the
43 * field-relative y direction.
44 * @param thetaController A profiled PID controller to respond to error in
45 * angle.
46 */
48 PIDController xController, PIDController yController,
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);
54 }
55
58 const HolonomicDriveController&) = default;
61 default;
62
63 /**
64 * Returns true if the pose error is within tolerance of the reference.
65 */
66 constexpr bool AtReference() const {
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();
71 return units::math::abs(eTranslate.X()) < tolTranslate.X() &&
72 units::math::abs(eTranslate.Y()) < tolTranslate.Y() &&
73 units::math::abs(eRotate.Radians()) < tolRotate.Radians();
74 }
75
76 /**
77 * Sets the pose error which is considered tolerable for use with
78 * AtReference().
79 *
80 * @param tolerance Pose error which is tolerable.
81 */
82 constexpr void SetTolerance(const Pose2d& tolerance) {
83 m_poseTolerance = tolerance;
84 }
85
86 /**
87 * Returns the next output of the holonomic drive controller.
88 *
89 * @param currentPose The current pose, as measured by odometry or pose
90 * estimator.
91 * @param trajectoryPose The desired trajectory pose, as sampled for the
92 * current timestep.
93 * @param desiredLinearVelocity The desired linear velocity.
94 * @param desiredHeading The desired heading.
95 * @return The next output of the holonomic drive controller.
96 */
98 const Pose2d& currentPose, const Pose2d& trajectoryPose,
99 units::meters_per_second_t desiredLinearVelocity,
100 const Rotation2d& desiredHeading) {
101 // If this is the first run, then we need to reset the theta controller to
102 // the current pose's heading.
103 if (m_firstRun) {
104 m_thetaController.Reset(currentPose.Rotation().Radians());
105 m_firstRun = false;
106 }
107
108 // Calculate feedforward velocities (field-relative)
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(
112 currentPose.Rotation().Radians(), desiredHeading.Radians())};
113
114 m_poseError = trajectoryPose.RelativeTo(currentPose);
115 m_rotationError = desiredHeading - currentPose.Rotation();
116
117 if (!m_enabled) {
118 return ChassisSpeeds::FromFieldRelativeSpeeds(xFF, yFF, thetaFF,
119 currentPose.Rotation());
120 }
121
122 // Calculate feedback velocities (based on position error).
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())};
127
128 // Return next output.
129 return ChassisSpeeds::FromFieldRelativeSpeeds(
130 xFF + xFeedback, yFF + yFeedback, thetaFF, currentPose.Rotation());
131 }
132
133 /**
134 * Returns the next output of the holonomic drive controller.
135 *
136 * @param currentPose The current pose, as measured by odometry or pose
137 * estimator.
138 * @param desiredState The desired trajectory pose, as sampled for the current
139 * timestep.
140 * @param desiredHeading The desired heading.
141 * @return The next output of the holonomic drive controller.
142 */
143 constexpr ChassisSpeeds Calculate(const Pose2d& currentPose,
144 const Trajectory::State& desiredState,
145 const Rotation2d& desiredHeading) {
146 return Calculate(currentPose, desiredState.pose, desiredState.velocity,
147 desiredHeading);
148 }
149
150 /**
151 * Enables and disables the controller for troubleshooting purposes. When
152 * Calculate() is called on a disabled controller, only feedforward values
153 * are returned.
154 *
155 * @param enabled If the controller is enabled or not.
156 */
157 constexpr void SetEnabled(bool enabled) { m_enabled = enabled; }
158
159 /**
160 * Returns the X PIDController
161 *
162 * @deprecated Use GetXController() instead.
163 */
164 [[deprecated("Use GetXController() instead")]]
166 return m_xController;
167 }
168
169 /**
170 * Returns the Y PIDController
171 *
172 * @deprecated Use GetYController() instead.
173 */
174 [[deprecated("Use GetYController() instead")]]
176 return m_yController;
177 }
178
179 /**
180 * Returns the rotation ProfiledPIDController
181 *
182 * @deprecated Use GetThetaController() instead.
183 */
184 [[deprecated("Use GetThetaController() instead")]]
186 return m_thetaController;
187 }
188
189 /**
190 * Returns the X PIDController
191 */
192 constexpr PIDController& GetXController() { return m_xController; }
193
194 /**
195 * Returns the Y PIDController
196 */
197 constexpr PIDController& GetYController() { return m_yController; }
198
199 /**
200 * Returns the rotation ProfiledPIDController
201 */
203 return m_thetaController;
204 }
205
206 private:
207 Pose2d m_poseError;
208 Rotation2d m_rotationError;
209 Pose2d m_poseTolerance;
210 bool m_enabled = true;
211
212 PIDController m_xController;
213 PIDController m_yController;
214 ProfiledPIDController<units::radian> m_thetaController;
215
216 bool m_firstRun = true;
217};
218} // namespace frc
#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 &currentPose, 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 &currentPose, 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
Definition CAN.h:11
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