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