29 units::meters_per_second_t vx = 0_mps;
34 units::meters_per_second_t vy = 0_mps;
39 units::radians_per_second_t omega = 0_rad_per_s;
61 units::meters_per_second_t vy,
62 units::radians_per_second_t omega,
64 Pose2d desiredDeltaPose{vx * dt, vy * dt, omega * dt};
65 auto twist =
Pose2d{}.
Log(desiredDeltaPose);
66 return {twist.
dx / dt, twist.dy / dt, twist.dtheta / dt};
88 return Discretize(continuousSpeeds.
vx, continuousSpeeds.
vy,
89 continuousSpeeds.
omega, dt);
109 units::meters_per_second_t vx, units::meters_per_second_t vy,
110 units::radians_per_second_t omega,
const Rotation2d& robotAngle) {
113 Translation2d{units::meter_t{vx.value()}, units::meter_t{vy.value()}}
115 return {units::meters_per_second_t{rotated.
X().value()},
116 units::meters_per_second_t{rotated.Y().value()}, omega};
135 return FromFieldRelativeSpeeds(fieldRelativeSpeeds.
vx,
136 fieldRelativeSpeeds.
vy,
137 fieldRelativeSpeeds.
omega, robotAngle);
157 units::meters_per_second_t vx, units::meters_per_second_t vy,
158 units::radians_per_second_t omega,
const Rotation2d& robotAngle) {
161 Translation2d{units::meter_t{vx.value()}, units::meter_t{vy.value()}}
163 return {units::meters_per_second_t{rotated.
X().value()},
164 units::meters_per_second_t{rotated.Y().value()}, omega};
183 return FromRobotRelativeSpeeds(robotRelativeSpeeds.
vx,
184 robotRelativeSpeeds.
vy,
185 robotRelativeSpeeds.
omega, robotAngle);
199 return {vx + other.
vx, vy + other.
vy, omega + other.
omega};
214 return *
this + -other;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Twist2d Log(const Pose2d &end) const
Returns a Twist2d that maps this pose to the end pose.
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a translation in 2D space.
Definition: Translation2d.h:27
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:76
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition: Translation2d.inc:27
Definition: AprilTagPoseEstimator.h:15
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
units::meters_per_second_t vx
Velocity along the x-axis.
Definition: ChassisSpeeds.h:29
units::meters_per_second_t vy
Velocity along the y-axis.
Definition: ChassisSpeeds.h:34
static ChassisSpeeds FromFieldRelativeSpeeds(const ChassisSpeeds &fieldRelativeSpeeds, const Rotation2d &robotAngle)
Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds obje...
Definition: ChassisSpeeds.h:133
units::radians_per_second_t omega
Represents the angular velocity of the robot frame.
Definition: ChassisSpeeds.h:39
static ChassisSpeeds Discretize(units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, units::second_t dt)
Disretizes a continuous-time chassis speed.
Definition: ChassisSpeeds.h:60
constexpr ChassisSpeeds operator+(const ChassisSpeeds &other) const
Adds two ChassisSpeeds and returns the sum.
Definition: ChassisSpeeds.h:198
static ChassisSpeeds FromRobotRelativeSpeeds(const ChassisSpeeds &robotRelativeSpeeds, const Rotation2d &robotAngle)
Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds obje...
Definition: ChassisSpeeds.h:181
static ChassisSpeeds FromRobotRelativeSpeeds(units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, const Rotation2d &robotAngle)
Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.
Definition: ChassisSpeeds.h:156
constexpr ChassisSpeeds operator-(const ChassisSpeeds &other) const
Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference.
Definition: ChassisSpeeds.h:213
static ChassisSpeeds Discretize(const ChassisSpeeds &continuousSpeeds, units::second_t dt)
Disretizes a continuous-time chassis speed.
Definition: ChassisSpeeds.h:86
static ChassisSpeeds FromFieldRelativeSpeeds(units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, const Rotation2d &robotAngle)
Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.
Definition: ChassisSpeeds.h:108
constexpr ChassisSpeeds operator*(double scalar) const
Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
Definition: ChassisSpeeds.h:235
constexpr ChassisSpeeds operator/(double scalar) const
Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
Definition: ChassisSpeeds.h:249
constexpr ChassisSpeeds operator-() const
Returns the inverse of the current ChassisSpeeds.
Definition: ChassisSpeeds.h:223
units::meter_t dx
Linear "dx" component.
Definition: Twist2d.h:25