WPILibC++  2020.3.2
DifferentialDriveWheelSpeeds.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 namespace frc {
20  units::meters_per_second_t left = 0_mps;
21 
25  units::meters_per_second_t right = 0_mps;
26 
37  void Normalize(units::meters_per_second_t attainableMaxSpeed);
38 };
39 } // namespace frc
frc::DifferentialDriveWheelSpeeds::right
units::meters_per_second_t right
Speed of the right side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:25
frc::DifferentialDriveWheelSpeeds::Normalize
void Normalize(units::meters_per_second_t attainableMaxSpeed)
Normalizes the wheel speeds using some max attainable speed.
frc::DifferentialDriveWheelSpeeds
Represents the wheel speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:16
frc::DifferentialDriveWheelSpeeds::left
units::meters_per_second_t left
Speed of the left side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:20
frc
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16