WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
SwerveModulePosition.hpp
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
8#include "wpi/units/length.hpp"
9#include "wpi/units/math.hpp"
12
13namespace wpi::math {
14/**
15 * Represents the position of one swerve module.
16 */
18 /**
19 * Distance the wheel of a module has traveled
20 */
21 wpi::units::meter_t distance = 0_m;
22
23 /**
24 * Angle of the module.
25 */
27
28 /**
29 * Checks equality between this SwerveModulePosition and another object.
30 *
31 * @param other The other object.
32 * @return Whether the two objects are equal.
33 */
34 constexpr bool operator==(const SwerveModulePosition& other) const {
35 return wpi::units::math::abs(distance - other.distance) < 1E-9_m &&
36 angle == other.angle;
37 }
38
40 const SwerveModulePosition& endValue, double t) const {
41 return {wpi::util::Lerp(distance, endValue.distance, t),
42 wpi::util::Lerp(angle, endValue.angle, t)};
43 }
44};
45} // namespace wpi::math
46
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Definition LinearSystem.hpp:20
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition MathExtras.hpp:780
Represents the position of one swerve module.
Definition SwerveModulePosition.hpp:17
constexpr bool operator==(const SwerveModulePosition &other) const
Checks equality between this SwerveModulePosition and another object.
Definition SwerveModulePosition.hpp:34
wpi::units::meter_t distance
Distance the wheel of a module has traveled.
Definition SwerveModulePosition.hpp:21
constexpr SwerveModulePosition Interpolate(const SwerveModulePosition &endValue, double t) const
Definition SwerveModulePosition.hpp:39
Rotation2d angle
Angle of the module.
Definition SwerveModulePosition.hpp:26