7#include "wpi/units/angle.hpp"
8#include "wpi/units/length.hpp"
9#include "wpi/units/math.hpp"
27 wpi::units::meter_t
dx = 0_m;
32 wpi::units::meter_t
dy = 0_m;
64 return wpi::units::math::abs(
dx - other.
dx) < 1E-9_m &&
65 wpi::units::math::abs(
dy - other.
dy) < 1E-9_m &&
87 const auto theta =
dtheta.value();
93 s = 1.0 - 1.0 / 6.0 * theta * theta;
97 c = (1 - cosTheta) / theta;
#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
Represents a translation in 2D space.
Definition Translation2d.hpp:30
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > cos(const T x) noexcept
Compile-time cosine function.
Definition cos.hpp:83
constexpr return_t< T > sin(const T x) noexcept
Compile-time sine function.
Definition sin.hpp:85
Definition LinearSystem.hpp:20
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.hpp:23
constexpr Transform2d Exp() const
Obtain a new Transform2d from a (constant curvature) velocity.
Definition Twist2d.hpp:86
constexpr Twist2d operator*(double factor) const
Scale this by a given factor.
Definition Twist2d.hpp:75
wpi::units::meter_t dy
Linear "dy" component.
Definition Twist2d.hpp:32
wpi::units::radian_t dtheta
Angular "dtheta" component (radians).
Definition Twist2d.hpp:37
constexpr bool operator==(const Twist2d &other) const
Checks equality between this Twist2d and another object.
Definition Twist2d.hpp:63
wpi::units::meter_t dx
Linear "dx" component.
Definition Twist2d.hpp:27