9#include "units/angle.h"
10#include "units/length.h"
11#include "units/math.h"
26 units::meter_t dx = 0_m;
31 units::meter_t dy = 0_m;
36 units::radian_t dtheta = 0_rad;
45 return units::math::abs(dx - other.dx) < 1E-9_m &&
46 units::math::abs(dy - other.dy) < 1E-9_m &&
47 units::math::abs(dtheta - other.dtheta) < 1E-9_rad;
57 return Twist2d{dx * factor, dy * factor, dtheta * factor};
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.h:22
constexpr Twist2d operator*(double factor) const
Scale this by a given factor.
Definition Twist2d.h:56
constexpr bool operator==(const Twist2d &other) const
Checks equality between this Twist2d and another object.
Definition Twist2d.h:44