WPILibC++  2020.3.2
SwerveModuleState.h
1 /*----------------------------------------------------------------------------*/
2 /* Copyright (c) 2019 FIRST. All Rights Reserved. */
3 /* Open Source Software - may be modified and shared by FRC teams. The code */
4 /* must be accompanied by the FIRST BSD license file in the root directory of */
5 /* the project. */
6 /*----------------------------------------------------------------------------*/
7 
8 #pragma once
9 
10 #include <units/units.h>
11 
12 #include "frc/geometry/Rotation2d.h"
13 
14 namespace frc {
22  units::meters_per_second_t speed = 0_mps;
23 
28 };
29 } // namespace frc
frc::SwerveModuleState::speed
units::meters_per_second_t speed
Speed of the wheel of the module.
Definition: SwerveModuleState.h:22
frc::SwerveModuleState
Represents the state of one swerve module.
Definition: SwerveModuleState.h:18
frc::Rotation2d
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:22
frc::SwerveModuleState::angle
Rotation2d angle
Angle of the module.
Definition: SwerveModuleState.h:27
frc
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16