WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
LTVUnicycleController.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 <Eigen/Core>
8#include <wpi/SymbolExports.h>
9#include <wpi/array.h>
10
11#include "frc/StateSpaceUtil.h"
12#include "frc/geometry/Pose2d.h"
16#include "units/math.h"
17#include "units/time.h"
18#include "units/velocity.h"
19
20namespace frc {
21
22/**
23 * The linear time-varying unicycle controller has a similar form to the LQR,
24 * but the model used to compute the controller gain is the nonlinear unicycle
25 * model linearized around the drivetrain's current state.
26 *
27 * See section 8.9 in Controls Engineering in FRC for a derivation of the
28 * control law we used shown in theorem 8.9.1.
29 */
31 public:
32 /**
33 * Constructs a linear time-varying unicycle controller with default maximum
34 * desired error tolerances of (x = 0.0625 m, y = 0.125 m, heading = 2 rad)
35 * and default maximum desired control effort of (linear velocity = 1 m/s,
36 * angular velocity = 2 rad/s).
37 *
38 * @param dt Discretization timestep.
39 */
40 explicit LTVUnicycleController(units::second_t dt)
41 : LTVUnicycleController{{0.0625, 0.125, 2.0}, {1.0, 2.0}, dt} {}
42
43 /**
44 * Constructs a linear time-varying unicycle controller.
45 *
46 * See
47 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning
48 * for how to select the tolerances.
49 *
50 * @param Qelems The maximum desired error tolerance for each state (x, y,
51 * heading).
52 * @param Relems The maximum desired control effort for each input (linear
53 * velocity, angular velocity).
54 * @param dt Discretization timestep.
55 */
57 const wpi::array<double, 2>& Relems, units::second_t dt)
58 : m_Q{frc::MakeCostMatrix(Qelems)},
59 m_R{frc::MakeCostMatrix(Relems)},
60 m_dt{dt} {}
61
62 /**
63 * Move constructor.
64 */
66
67 /**
68 * Move assignment operator.
69 */
71
72 /**
73 * Returns true if the pose error is within tolerance of the reference.
74 */
75 bool AtReference() const {
76 const auto& eTranslate = m_poseError.Translation();
77 const auto& eRotate = m_poseError.Rotation();
78 const auto& tolTranslate = m_poseTolerance.Translation();
79 const auto& tolRotate = m_poseTolerance.Rotation();
80 return units::math::abs(eTranslate.X()) < tolTranslate.X() &&
81 units::math::abs(eTranslate.Y()) < tolTranslate.Y() &&
82 units::math::abs(eRotate.Radians()) < tolRotate.Radians();
83 }
84
85 /**
86 * Sets the pose error which is considered tolerable for use with
87 * AtReference().
88 *
89 * @param poseTolerance Pose error which is tolerable.
90 */
91 void SetTolerance(const Pose2d& poseTolerance) {
92 m_poseTolerance = poseTolerance;
93 }
94
95 /**
96 * Returns the linear and angular velocity outputs of the LTV controller.
97 *
98 * The reference pose, linear velocity, and angular velocity should come from
99 * a drivetrain trajectory.
100 *
101 * @param currentPose The current pose.
102 * @param poseRef The desired pose.
103 * @param linearVelocityRef The desired linear velocity.
104 * @param angularVelocityRef The desired angular velocity.
105 */
106 ChassisSpeeds Calculate(const Pose2d& currentPose, const Pose2d& poseRef,
107 units::meters_per_second_t linearVelocityRef,
108 units::radians_per_second_t angularVelocityRef);
109
110 /**
111 * Returns the linear and angular velocity outputs of the LTV controller.
112 *
113 * The reference pose, linear velocity, and angular velocity should come from
114 * a drivetrain trajectory.
115 *
116 * @param currentPose The current pose.
117 * @param desiredState The desired pose, linear velocity, and angular velocity
118 * from a trajectory.
119 */
120 ChassisSpeeds Calculate(const Pose2d& currentPose,
121 const Trajectory::State& desiredState) {
122 return Calculate(currentPose, desiredState.pose, desiredState.velocity,
123 desiredState.velocity * desiredState.curvature);
124 }
125
126 /**
127 * Enables and disables the controller for troubleshooting purposes.
128 *
129 * @param enabled If the controller is enabled or not.
130 */
131 void SetEnabled(bool enabled) { m_enabled = enabled; }
132
133 private:
134 // LQR cost matrices
135 Eigen::Matrix<double, 3, 3> m_Q;
136 Eigen::Matrix<double, 2, 2> m_R;
137
138 units::second_t m_dt;
139
140 Pose2d m_poseError;
141 Pose2d m_poseTolerance;
142 bool m_enabled = true;
143};
144
145} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
The linear time-varying unicycle controller has a similar form to the LQR, but the model used to comp...
Definition LTVUnicycleController.h:30
LTVUnicycleController(units::second_t dt)
Constructs a linear time-varying unicycle controller with default maximum desired error tolerances of...
Definition LTVUnicycleController.h:40
void SetTolerance(const Pose2d &poseTolerance)
Sets the pose error which is considered tolerable for use with AtReference().
Definition LTVUnicycleController.h:91
LTVUnicycleController & operator=(LTVUnicycleController &&)=default
Move assignment operator.
ChassisSpeeds Calculate(const Pose2d &currentPose, const Pose2d &poseRef, units::meters_per_second_t linearVelocityRef, units::radians_per_second_t angularVelocityRef)
Returns the linear and angular velocity outputs of the LTV controller.
bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
Definition LTVUnicycleController.h:75
void SetEnabled(bool enabled)
Enables and disables the controller for troubleshooting purposes.
Definition LTVUnicycleController.h:131
LTVUnicycleController(LTVUnicycleController &&)=default
Move constructor.
LTVUnicycleController(const wpi::array< double, 3 > &Qelems, const wpi::array< double, 2 > &Relems, units::second_t dt)
Constructs a linear time-varying unicycle controller.
Definition LTVUnicycleController.h:56
ChassisSpeeds Calculate(const Pose2d &currentPose, const Trajectory::State &desiredState)
Returns the linear and angular velocity outputs of the LTV controller.
Definition LTVUnicycleController.h:120
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
Definition SystemServer.h:9
constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(Ts... tolerances)
Creates a cost matrix from the given vector for use with LQR.
Definition StateSpaceUtil.h:37
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
units::curvature_t curvature
The curvature at that point of the trajectory.
Definition Trajectory.h:48