9#include "units/angle.h"
10#include "units/length.h"
11#include "units/math.h"
28 units::meter_t dx = 0_m;
33 units::meter_t dy = 0_m;
38 units::radian_t dtheta = 0_rad;
65 return units::math::abs(dx - other.dx) < 1E-9_m &&
66 units::math::abs(dy - other.dy) < 1E-9_m &&
67 units::math::abs(dtheta - other.dtheta) < 1E-9_rad;
77 return Twist2d{dx * factor, dy * factor, dtheta * factor};
88 const auto theta =
dtheta.value();
94 s = 1.0 - 1.0 / 6.0 * theta * theta;
98 c = (1 - cosTheta) / theta;
#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:26
Represents a translation in 2D space.
Definition Translation2d.h:30
Definition SystemServer.h:9
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
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.h:24
units::meter_t dy
Linear "dy" component.
Definition Twist2d.h:33
constexpr Twist2d operator*(double factor) const
Scale this by a given factor.
Definition Twist2d.h:76
units::meter_t dx
Linear "dx" component.
Definition Twist2d.h:28
constexpr Transform2d Exp() const
Obtain a new Transform2d from a (constant curvature) velocity.
Definition Twist2d.h:87
constexpr bool operator==(const Twist2d &other) const
Checks equality between this Twist2d and another object.
Definition Twist2d.h:64
units::radian_t dtheta
Angular "dtheta" component (radians)
Definition Twist2d.h:38