CTRE Phoenix 6 C++ 25.0.0-beta-4
Loading...
Searching...
No Matches
SwerveDriveKinematics.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
10#include <units/angular_velocity.h>
11#include <units/velocity.h>
12#include <memory>
13#include <vector>
14
15namespace ctre {
16namespace phoenix6 {
17namespace swerve {
18namespace impl {
19
20/**
21 * \brief Class that converts a chassis velocity (dx, dy, and dtheta components)
22 * into individual module states (speed and angle).
23 *
24 * The inverse kinematics (converting from a desired chassis velocity to
25 * individual module states) uses the relative locations of the modules with
26 * respect to the center of rotation. The center of rotation for inverse
27 * kinematics is also variable. This means that you can set your set your center
28 * of rotation in a corner of the robot to perform special evasion maneuvers.
29 *
30 * Forward kinematics (converting an array of module states into the overall
31 * chassis motion) is performs the exact opposite of what inverse kinematics
32 * does. Since this is an overdetermined system (more equations than variables),
33 * we use a least-squares approximation.
34 *
35 * The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds]
36 * We take the Moore-Penrose pseudoinverse of [moduleLocations] and then
37 * multiply by [moduleStates] to get our chassis speeds.
38 *
39 * Forward kinematics is also used for odometry -- determining the position of
40 * the robot on the field using encoders and a gyro.
41 */
43 size_t m_numModules;
44 std::vector<Translation2d> m_moduleLocations;
45
46 struct KinematicsMatrices;
47 std::unique_ptr<KinematicsMatrices> m_matrices;
48
49 std::vector<Rotation2d> m_lastModuleHeading;
50 Translation2d m_lastCOR{};
51
52public:
53 using WheelSpeeds = std::vector<SwerveModuleState>;
54 using WheelPositions = std::vector<SwerveModulePosition>;
55
56 /**
57 * \brief Constructs a swerve drive kinematics object. This takes in a variable
58 * number of module locations as Translation2ds. The order in which you pass
59 * in the module locations is the same order that you will receive the module
60 * states when performing inverse kinematics. It is also expected that you
61 * pass in the module states in the same order when calling the forward
62 * kinematics methods.
63 *
64 * \param moduleLocations The locations of the modules relative to the
65 * physical center of the robot.
66 */
67 SwerveDriveKinematics(std::vector<Translation2d> moduleLocations);
68
72
75
76 /**
77 * \brief Reset the internal swerve module headings.
78 *
79 * \param moduleHeadings The swerve module headings. The order of the module
80 * headings should be same as passed into the constructor of this class.
81 */
82 void ResetHeadings(std::vector<Rotation2d> const &moduleHeadings)
83 {
84 for (size_t i = 0; i < m_numModules && i < moduleHeadings.size(); ++i) {
85 m_lastModuleHeading[i] = moduleHeadings[i];
86 }
87 }
88
89 /**
90 * \brief Performs inverse kinematics to return the module states from a desired
91 * chassis velocity. This method is often used to convert joystick values into
92 * module speeds and angles.
93 *
94 * This function also supports variable centers of rotation. During normal
95 * operations, the center of rotation is usually the same as the physical
96 * center of the robot; therefore, the argument is defaulted to that use case.
97 * However, if you wish to change the center of rotation for evasive
98 * maneuvers, vision alignment, or for any other use case, you can do so.
99 *
100 * In the case that the desired chassis speeds are zero (i.e. the robot will
101 * be stationary), the previously calculated module angle will be maintained.
102 *
103 * \param chassisSpeeds The desired chassis speed.
104 * \param centerOfRotation The center of rotation. For example, if you set the
105 * center of rotation at one corner of the robot and provide a chassis speed
106 * that only has a dtheta component, the robot will rotate around that corner.
107 *
108 * \returns A vector containing the module states. Use caution because these
109 * module states are not normalized. Sometimes, a user input may cause one of
110 * the module speeds to go above the attainable max velocity. Use the
111 * DesaturateWheelSpeeds(WheelSpeeds*, units::meters_per_second_t) function to
112 * rectify this issue.
113 */
114 WheelSpeeds ToSwerveModuleStates(ChassisSpeeds const &chassisSpeeds, Translation2d const &centerOfRotation = Translation2d{});
115
116 /**
117 * \brief Performs forward kinematics to return the resulting chassis state from the
118 * given module states. This method is often used for odometry -- determining
119 * the robot's position on the field using data from the real-world speed and
120 * angle of each module on the robot.
121 *
122 * \param moduleStates The state of the modules as a std::vector of type
123 * SwerveModuleState as measured from respective encoders and gyros. The
124 * order of the swerve module states should be same as passed into the
125 * constructor of this class.
126 *
127 * \returns The resulting chassis speed.
128 */
129 ChassisSpeeds ToChassisSpeeds(WheelSpeeds const &moduleStates) const;
130
131 /**
132 * \brief Performs forward kinematics to return the resulting Twist2d from the
133 * given module position deltas. This method is often used for odometry --
134 * determining the robot's position on the field using data from the
135 * real-world position delta and angle of each module on the robot.
136 *
137 * \param moduleDeltas The latest change in position of the modules (as a
138 * SwerveModulePosition type) as measured from respective encoders and gyros.
139 * The order of the swerve module states should be same as passed into the
140 * constructor of this class.
141 *
142 * \returns The resulting Twist2d.
143 */
144 Twist2d ToTwist2d(WheelPositions const &moduleDeltas) const;
145
146 /**
147 * \brief Performs forward kinematics to return the resulting Twist2d from the given
148 * change in wheel positions. This method is often used for odometry --
149 * determining the robot's position on the field using changes in the distance
150 * driven by each wheel on the robot.
151 *
152 * \param start The starting distances driven by the wheels.
153 * \param end The ending distances driven by the wheels.
154 *
155 * \returns The resulting Twist2d in the robot's movement.
156 */
157 Twist2d ToTwist2d(WheelPositions const &start, WheelPositions const &end) const
158 {
159 WheelPositions result(m_numModules);
160 for (size_t i = 0; i < m_numModules && i < std::min(start.size(), end.size()); ++i) {
161 result[i] = {end[i].distance - start[i].distance, end[i].angle};
162 }
163 return ToTwist2d(result);
164 }
165
166 /**
167 * \brief Performs interpolation between two values.
168 *
169 * \param start The value to start at.
170 * \param end The value to end at.
171 * \param t How far between the two values to interpolate. This should be
172 * bounded to [0, 1].
173 * \returns The interpolated value.
174 */
175 WheelPositions Interpolate(WheelPositions const &start, WheelPositions const &end, double t) const
176 {
177 WheelPositions result(m_numModules);
178 for (size_t i = 0; i < m_numModules && i < std::min(start.size(), end.size()); ++i) {
179 result[i] = start[i].Interpolate(end[i], t);
180 }
181 return result;
182 }
183
184 /**
185 * \brief Renormalizes the wheel speeds if any individual speed is above the
186 * specified maximum.
187 *
188 * Sometimes, after inverse kinematics, the requested speed
189 * from one or more modules may be above the max attainable speed for the
190 * driving motor on that module. To fix this issue, one can reduce all the
191 * wheel speeds to make sure that all requested module speeds are at-or-below
192 * the absolute threshold, while maintaining the ratio of speeds between
193 * modules.
194 *
195 * \param moduleStates Reference to vector of module states. The vector will be
196 * mutated with the normalized speeds!
197 * \param attainableMaxSpeed The absolute max speed that a module can reach.
198 */
199 static void DesaturateWheelSpeeds(WheelSpeeds *moduleStates, units::meters_per_second_t attainableMaxSpeed);
200};
201
202}
203}
204}
205}
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:42
SwerveDriveKinematics(std::vector< Translation2d > moduleLocations)
Constructs a swerve drive kinematics object.
Twist2d ToTwist2d(WheelPositions const &start, WheelPositions const &end) const
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
Definition SwerveDriveKinematics.hpp:157
std::vector< SwerveModulePosition > WheelPositions
Definition SwerveDriveKinematics.hpp:54
SwerveDriveKinematics & operator=(SwerveDriveKinematics const &)
static void DesaturateWheelSpeeds(WheelSpeeds *moduleStates, units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
ChassisSpeeds ToChassisSpeeds(WheelSpeeds const &moduleStates) const
Performs forward kinematics to return the resulting chassis state from the given module states.
WheelPositions Interpolate(WheelPositions const &start, WheelPositions const &end, double t) const
Performs interpolation between two values.
Definition SwerveDriveKinematics.hpp:175
WheelSpeeds ToSwerveModuleStates(ChassisSpeeds const &chassisSpeeds, Translation2d const &centerOfRotation=Translation2d{})
Performs inverse kinematics to return the module states from a desired chassis velocity.
SwerveDriveKinematics(SwerveDriveKinematics const &)
SwerveDriveKinematics & operator=(SwerveDriveKinematics &&)
void ResetHeadings(std::vector< Rotation2d > const &moduleHeadings)
Reset the internal swerve module headings.
Definition SwerveDriveKinematics.hpp:82
Twist2d ToTwist2d(WheelPositions const &moduleDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given module position deltas.
std::vector< SwerveModuleState > WheelSpeeds
Definition SwerveDriveKinematics.hpp:53
Definition StatusCodes.h:18