WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
SwerveModuleState.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
10#include "units/angle.h"
11#include "units/math.h"
12#include "units/velocity.h"
13
14namespace frc {
15/**
16 * Represents the state of one swerve module.
17 */
19 /**
20 * Speed of the wheel of the module.
21 */
22 units::meters_per_second_t speed = 0_mps;
23
24 /**
25 * Angle of the module.
26 */
28
29 /**
30 * Checks equality between this SwerveModuleState and another object.
31 *
32 * @param other The other object.
33 * @return Whether the two objects are equal.
34 */
35 constexpr bool operator==(const SwerveModuleState& other) const {
36 return units::math::abs(speed - other.speed) < 1E-9_mps &&
37 angle == other.angle;
38 }
39
40 /**
41 * Minimize the change in the heading this swerve module state would
42 * require by potentially reversing the direction the wheel spins. If this is
43 * used with the PIDController class's continuous input functionality, the
44 * furthest a wheel will ever rotate is 90 degrees.
45 *
46 * @param currentAngle The current module angle.
47 */
48 constexpr void Optimize(const Rotation2d& currentAngle) {
49 auto delta = angle - currentAngle;
50 if (units::math::abs(delta.Degrees()) > 90_deg) {
51 speed *= -1;
52 angle = angle + Rotation2d{180_deg};
53 }
54 }
55
56 /**
57 * Minimize the change in heading the desired swerve module state would
58 * require by potentially reversing the direction the wheel spins. If this is
59 * used with the PIDController class's continuous input functionality, the
60 * furthest a wheel will ever rotate is 90 degrees.
61 *
62 * @param desiredState The desired state.
63 * @param currentAngle The current module angle.
64 */
65 [[deprecated("Use instance method instead.")]]
66 constexpr static SwerveModuleState Optimize(
67 const SwerveModuleState& desiredState, const Rotation2d& currentAngle) {
68 auto delta = desiredState.angle - currentAngle;
69 if (units::math::abs(delta.Degrees()) > 90_deg) {
70 return {-desiredState.speed, desiredState.angle + Rotation2d{180_deg}};
71 } else {
72 return {desiredState.speed, desiredState.angle};
73 }
74 }
75
76 /**
77 * Scales speed by cosine of angle error. This scales down movement
78 * perpendicular to the desired direction of travel that can occur when
79 * modules change directions. This results in smoother driving.
80 *
81 * @param currentAngle The current module angle.
82 */
83 constexpr void CosineScale(const Rotation2d& currentAngle) {
84 speed *= (angle - currentAngle).Cos();
85 }
86};
87} // namespace frc
88
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
Definition CAN.h:11
Represents the state of one swerve module.
Definition SwerveModuleState.h:18
static constexpr SwerveModuleState Optimize(const SwerveModuleState &desiredState, const Rotation2d &currentAngle)
Minimize the change in heading the desired swerve module state would require by potentially reversing...
Definition SwerveModuleState.h:66
constexpr void CosineScale(const Rotation2d &currentAngle)
Scales speed by cosine of angle error.
Definition SwerveModuleState.h:83
units::meters_per_second_t speed
Speed of the wheel of the module.
Definition SwerveModuleState.h:22
Rotation2d angle
Angle of the module.
Definition SwerveModuleState.h:27
constexpr void Optimize(const Rotation2d &currentAngle)
Minimize the change in the heading this swerve module state would require by potentially reversing th...
Definition SwerveModuleState.h:48
constexpr bool operator==(const SwerveModuleState &other) const
Checks equality between this SwerveModuleState and another object.
Definition SwerveModuleState.h:35