WPILibC++ 2024.3.2
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 <wpi/SymbolExports.h>
8
11#include "frc/geometry/Pose2d.h"
15#include "units/angle.h"
16#include "units/velocity.h"
17
18namespace frc {
19/**
20 * This holonomic drive controller can be used to follow trajectories using a
21 * holonomic drivetrain (i.e. swerve or mecanum). Holonomic trajectory following
22 * is a much simpler problem to solve compared to skid-steer style drivetrains
23 * because it is possible to individually control forward, sideways, and angular
24 * velocity.
25 *
26 * The holonomic drive controller takes in one PID controller for each
27 * direction, forward and sideways, and one profiled PID controller for the
28 * angular direction. Because the heading dynamics are decoupled from
29 * translations, users can specify a custom heading that the drivetrain should
30 * point toward. This heading reference is profiled for smoothness.
31 */
33 public:
34 /**
35 * Constructs a holonomic drive controller.
36 *
37 * @param xController A PID Controller to respond to error in the
38 * field-relative x direction.
39 * @param yController A PID Controller to respond to error in the
40 * field-relative y direction.
41 * @param thetaController A profiled PID controller to respond to error in
42 * angle.
43 */
45 PIDController xController, PIDController yController,
47
50 default;
53
54 /**
55 * Returns true if the pose error is within tolerance of the reference.
56 */
57 bool AtReference() const;
58
59 /**
60 * Sets the pose error which is considered tolerable for use with
61 * AtReference().
62 *
63 * @param tolerance Pose error which is tolerable.
64 */
65 void SetTolerance(const Pose2d& tolerance);
66
67 /**
68 * Returns the next output of the holonomic drive controller.
69 *
70 * @param currentPose The current pose, as measured by odometry or pose
71 * estimator.
72 * @param trajectoryPose The desired trajectory pose, as sampled for the
73 * current timestep.
74 * @param desiredLinearVelocity The desired linear velocity.
75 * @param desiredHeading The desired heading.
76 * @return The next output of the holonomic drive controller.
77 */
78 ChassisSpeeds Calculate(const Pose2d& currentPose,
79 const Pose2d& trajectoryPose,
80 units::meters_per_second_t desiredLinearVelocity,
81 const Rotation2d& desiredHeading);
82
83 /**
84 * Returns the next output of the holonomic drive controller.
85 *
86 * @param currentPose The current pose, as measured by odometry or pose
87 * estimator.
88 * @param desiredState The desired trajectory pose, as sampled for the current
89 * timestep.
90 * @param desiredHeading The desired heading.
91 * @return The next output of the holonomic drive controller.
92 */
93 ChassisSpeeds Calculate(const Pose2d& currentPose,
94 const Trajectory::State& desiredState,
95 const Rotation2d& desiredHeading);
96
97 /**
98 * Enables and disables the controller for troubleshooting purposes. When
99 * Calculate() is called on a disabled controller, only feedforward values
100 * are returned.
101 *
102 * @param enabled If the controller is enabled or not.
103 */
104 void SetEnabled(bool enabled);
105
106 /**
107 * Returns the rotation ProfiledPIDController
108 */
110
111 /**
112 * Returns the X PIDController
113 */
115
116 /**
117 * Returns the Y PIDController
118 */
120
121 private:
122 Pose2d m_poseError;
123 Rotation2d m_rotationError;
124 Pose2d m_poseTolerance;
125 bool m_enabled = true;
126
127 PIDController m_xController;
128 PIDController m_yController;
129 ProfiledPIDController<units::radian> m_thetaController;
130
131 bool m_firstRun = true;
132};
133} // 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:32
PIDController & getYController()
Returns the Y PIDController.
ProfiledPIDController< units::radian > & getThetaController()
Returns the rotation ProfiledPIDController.
ChassisSpeeds Calculate(const Pose2d &currentPose, const Trajectory::State &desiredState, const Rotation2d &desiredHeading)
Returns the next output of the holonomic drive controller.
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.
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