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