10 #include <units/units.h>
12 #include "frc/geometry/Rotation2d.h"
30 units::meters_per_second_t
vx = 0_mps;
35 units::meters_per_second_t
vy = 0_mps;
40 units::radians_per_second_t
omega = 0_rad_per_s;
59 units::meters_per_second_t
vx, units::meters_per_second_t
vy,
61 return {
vx * robotAngle.
Cos() +
vy * robotAngle.
Sin(),
double Cos() const
Returns the cosine of the rotation.
Definition: Rotation2d.h:160
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:22
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:58
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:26
double Sin() const
Returns the sine of the rotation.
Definition: Rotation2d.h:167
units::radians_per_second_t omega
Represents the angular velocity of the robot frame.
Definition: ChassisSpeeds.h:40
units::meters_per_second_t vy
Represents strafe velocity w.r.t the robot frame of reference.
Definition: ChassisSpeeds.h:35
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16
units::meters_per_second_t vx
Represents forward velocity w.r.t the robot frame of reference.
Definition: ChassisSpeeds.h:30